From fe0d810713885b6d348c2b408ce75e5606c5a73d Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 6 May 2026 21:35:42 +0200 Subject: [PATCH 01/23] feat(g1-wbc): groot-wbc real-hw + sim blueprints --- data/.lfs/groot.tar.gz | 3 + data/.lfs/mujoco_sim.tar.gz | 4 +- dimos/control/components.py | 49 + dimos/control/coordinator.py | 237 ++++- dimos/control/hardware_interface.py | 37 +- dimos/control/tasks/groot_wbc_task.py | 642 +++++++++++++ dimos/control/tasks/servo_task.py | 15 + dimos/control/tasks/test_groot_wbc_task.py | 463 ++++++++++ dimos/control/tick_loop.py | 31 + dimos/core/global_config.py | 1 + .../drive_trains/unitree_g1/__init__.py | 19 + .../drive_trains/unitree_g1/adapter.py | 400 ++++++++ .../drive_trains/unitree_go2/__init__.py | 19 + dimos/hardware/whole_body/__init__.py | 15 + dimos/hardware/whole_body/mujoco/__init__.py | 0 .../hardware/whole_body/mujoco/g1/__init__.py | 0 .../hardware/whole_body/mujoco/g1/adapter.py | 220 +++++ dimos/hardware/whole_body/registry.py | 41 +- dimos/hardware/whole_body/spec.py | 104 ++- dimos/hardware/whole_body/unitree/__init__.py | 15 + .../whole_body/unitree/g1/__init__.py | 0 .../hardware/whole_body/unitree/g1/adapter.py | 302 ++++++ .../whole_body/unitree/go2/__init__.py | 15 + .../whole_body/unitree/go2/adapter.py | 254 ++++++ dimos/robot/all_blueprints.py | 2 + .../g1/blueprints/basic/_groot_wbc_common.py | 116 +++ .../blueprints/basic/unitree_g1_groot_wbc.py | 145 +++ .../basic/unitree_g1_groot_wbc_sim.py | 124 +++ dimos/robot/unitree/g1/system_prompt.py | 5 + dimos/simulation/engines/mujoco_engine.py | 56 +- dimos/simulation/engines/mujoco_shm.py | 124 ++- dimos/simulation/engines/mujoco_sim_module.py | 354 ++++++- dimos/simulation/mujoco/model.py | 19 +- pyproject.toml | 43 +- uv.lock | 862 +++++++++++++++--- 35 files changed, 4530 insertions(+), 206 deletions(-) create mode 100644 data/.lfs/groot.tar.gz create mode 100644 dimos/control/tasks/groot_wbc_task.py create mode 100644 dimos/control/tasks/test_groot_wbc_task.py create mode 100644 dimos/hardware/drive_trains/unitree_g1/__init__.py create mode 100644 dimos/hardware/drive_trains/unitree_g1/adapter.py create mode 100644 dimos/hardware/drive_trains/unitree_go2/__init__.py create mode 100644 dimos/hardware/whole_body/__init__.py create mode 100644 dimos/hardware/whole_body/mujoco/__init__.py create mode 100644 dimos/hardware/whole_body/mujoco/g1/__init__.py create mode 100644 dimos/hardware/whole_body/mujoco/g1/adapter.py create mode 100644 dimos/hardware/whole_body/unitree/__init__.py create mode 100644 dimos/hardware/whole_body/unitree/g1/__init__.py create mode 100644 dimos/hardware/whole_body/unitree/g1/adapter.py create mode 100644 dimos/hardware/whole_body/unitree/go2/__init__.py create mode 100644 dimos/hardware/whole_body/unitree/go2/adapter.py create mode 100644 dimos/robot/unitree/g1/blueprints/basic/_groot_wbc_common.py create mode 100644 dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc.py create mode 100644 dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py diff --git a/data/.lfs/groot.tar.gz b/data/.lfs/groot.tar.gz new file mode 100644 index 0000000000..16602bca84 --- /dev/null +++ b/data/.lfs/groot.tar.gz @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:305ed4b8538cb8083d91518e687b184b374c977afd185adecabc1152cef8d701 +size 3517892 diff --git a/data/.lfs/mujoco_sim.tar.gz b/data/.lfs/mujoco_sim.tar.gz index 57833fbbc6..47d2df201d 100644 --- a/data/.lfs/mujoco_sim.tar.gz +++ b/data/.lfs/mujoco_sim.tar.gz @@ -1,3 +1,3 @@ version https://git-lfs.github.com/spec/v1 -oid sha256:d178439569ed81dfad05455419dc51da2c52021313b6d7b9259d9e30946db7c6 -size 60186340 +oid sha256:4232d61e4af19dee0c0e3a8f55f2c1b48b28a70f810ff17039876a48b999d6d2 +size 60251722 diff --git a/dimos/control/components.py b/dimos/control/components.py index 04ca6f03a7..09370ca392 100644 --- a/dimos/control/components.py +++ b/dimos/control/components.py @@ -18,6 +18,8 @@ from enum import Enum from typing import Any +from dimos.hardware.whole_body.spec import WholeBodyConfig + HardwareId = str JointName = str TaskName = str @@ -37,6 +39,7 @@ def split_joint_name(joint_name: str) -> tuple[str, str]: class HardwareType(Enum): MANIPULATOR = "manipulator" BASE = "base" + GRIPPER = "gripper" WHOLE_BODY = "whole_body" @@ -61,6 +64,16 @@ class HardwareComponent: address: Connection address - IP for TCP, port for CAN auto_enable: Whether to auto-enable servos gripper_joints: Joints that use adapter gripper methods (separate from joints). + domain_id: DDS domain ID for adapters that use DDS transport + (e.g. Unitree G1). Real robot uses 0; unitree_mujoco sim + defaults to 1. Ignored by non-DDS adapters. + adapter_kwargs: Generic untyped kwargs forwarded to the adapter + constructor — use for adapter-specific knobs that don't + belong in the spec. + wb_config: Whole-body-specific config (PD gains etc.). Populate + on hardware_type=WHOLE_BODY components. Keeps WB-only knobs + off the generic HardwareComponent shared by manipulators, + bases, and grippers. """ hardware_id: HardwareId @@ -70,7 +83,9 @@ class HardwareComponent: address: str | None = None auto_enable: bool = True gripper_joints: list[JointName] = field(default_factory=list) + domain_id: int = 0 adapter_kwargs: dict[str, Any] = field(default_factory=dict) + wb_config: WholeBodyConfig | None = None @property def all_joints(self) -> list[JointName]: @@ -136,6 +151,39 @@ def make_twist_base_joints( return [f"{hardware_id}/{s}" for s in suffixes] +_QUADRUPED_LEG_JOINTS = [ + "FR_0", + "FR_1", + "FR_2", + "FL_0", + "FL_1", + "FL_2", + "RR_0", + "RR_1", + "RR_2", + "RL_0", + "RL_1", + "RL_2", +] + + +def make_quadruped_joints(hardware_id: HardwareId) -> list[JointName]: + """Create joint names for a 12-DOF quadruped. + + Uses standard leg naming: FR/FL/RR/RL with 3 joints each + (hip, thigh, calf). Slash-separated to match + ``split_joint_name`` (consistent with ``make_humanoid_joints`` + and ``make_twist_base_joints``). + + Args: + hardware_id: The hardware identifier (e.g., "go2") + + Returns: + List of 12 joint names like ["go2/FR_0", "go2/FR_1", ..., "go2/RL_2"] + """ + return [f"{hardware_id}/{j}" for j in _QUADRUPED_LEG_JOINTS] + + _HUMANOID_29DOF_JOINTS = [ # Left leg (0-5) "left_hip_pitch", @@ -199,6 +247,7 @@ def make_humanoid_joints(hardware_id: HardwareId) -> list[JointName]: "make_gripper_joints", "make_humanoid_joints", "make_joints", + "make_quadruped_joints", "make_twist_base_joints", "split_joint_name", ] diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index 13c959cd89..fe526d128f 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -58,6 +58,7 @@ from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped from dimos.msgs.geometry_msgs.Twist import Twist from dimos.msgs.sensor_msgs.JointState import JointState +from dimos.msgs.std_msgs.Bool import Bool from dimos.teleop.quest.quest_types import ( Buttons, ) @@ -75,22 +76,26 @@ class TaskConfig: Attributes: name: Task name (e.g., "traj_arm") - type: Task type ("trajectory", "servo", "velocity", "cartesian_ik", "teleop_ik") + type: Task type ("trajectory", "servo", "velocity", "cartesian_ik", "teleop_ik", "groot_wbc") joint_names: List of joint names this task controls priority: Task priority (higher wins arbitration) - model_path: Path to URDF/MJCF for IK solver (cartesian_ik/teleop_ik only) + model_path: Path to URDF/MJCF for IK solver (cartesian_ik/teleop_ik) + or directory containing balance.onnx/walk.onnx (groot_wbc). ee_joint_id: End-effector joint ID in model (cartesian_ik/teleop_ik only) hand: "left" or "right" controller hand (teleop_ik only) gripper_joint: Joint name for gripper virtual joint gripper_open_pos: Gripper position at trigger 0.0 gripper_closed_pos: Gripper position at trigger 1.0 + hardware_id: Hardware id this task reads extra state from + (required by groot_wbc — pulls the WholeBodyAdapter for IMU + and the full joint list for observation assembly). """ name: str type: str = "trajectory" joint_names: list[str] = field(default_factory=lambda: []) priority: int = 10 - # Cartesian IK / Teleop IK specific + # Cartesian IK / Teleop IK / GR00T WBC specific model_path: str | Path | None = None ee_joint_id: int = 6 hand: Literal["left", "right"] | None = None # teleop_ik only @@ -98,6 +103,35 @@ class TaskConfig: gripper_joint: str | None = None gripper_open_pos: float = 0.0 gripper_closed_pos: float = 0.0 + # Tasks that need a hardware reference (e.g. groot_wbc for IMU + 29-DOF state) + hardware_id: str | None = None + # Servo task: optional initial target held until/unless a new one arrives. + default_positions: list[float] | None = None + # Call ``task.start()`` right after registration so the task is live + # from the first tick (e.g. GR00T balance/walk needs to drive joints + # immediately). Default False keeps the existing convention where + # tasks wait for an explicit activation (e.g. from teleop). + auto_start: bool = False + # Arm the task's policy automatically on ``start()`` (applies to + # tasks exposing ``arm()``, e.g. ``GrootWBCTask``). Simulation + # blueprints set this True; real-hardware blueprints leave it False + # so the operator arms via dashboard button after settling. + auto_arm: bool = False + # Start the task in dry-run mode (policy computes but output is + # suppressed). For real-hardware safety checks. + auto_dry_run: bool = False + # Ramp duration (seconds) used by ``arm()`` when called without an + # explicit argument — applies to tasks that interpolate from the + # current pose toward a default on arming. + default_ramp_seconds: float = 10.0 + # GR00T WBC only: run policy inference every N coordinator ticks. + # Effective policy rate = ``tick_rate / decimation``. The model was + # trained at 50 Hz, so the original convention was tick_rate=500 + + # decimation=10. At tick_rate=50 set decimation=1 (matches upstream + # `run_g1_control_loop.py` which spins the policy directly at 50 Hz). + # Mismatched rates make the policy hold actions for too long and + # the robot tips over. ``None`` keeps the task's own default (10). + decimation: int | None = None class ControlCoordinatorConfig(ModuleConfig): @@ -107,6 +141,9 @@ class ControlCoordinatorConfig(ModuleConfig): tick_rate: Control loop frequency in Hz (default: 100) publish_joint_state: Whether to publish aggregated JointState joint_state_frame_id: Frame ID for published JointState + publish_odom: Whether to poll WholeBodyAdapter.read_odom() each + tick and publish on the ``odom`` Out port (silent no-op when + no adapter exposes odom). log_ticks: Whether to log tick information (verbose) hardware: List of hardware configurations to create on start tasks: List of task configurations to create on start @@ -115,6 +152,7 @@ class ControlCoordinatorConfig(ModuleConfig): tick_rate: float = 100.0 publish_joint_state: bool = True joint_state_frame_id: str = "coordinator" + publish_odom: bool = True log_ticks: bool = False hardware: list[HardwareComponent] = field(default_factory=lambda: []) tasks: list[TaskConfig] = field(default_factory=lambda: []) @@ -153,6 +191,11 @@ class ControlCoordinator(Module): # Output: Aggregated joint state for external consumers joint_state: Out[JointState] + # Output: Latest base pose, when any whole-body adapter exposes one + # via ``read_odom()`` (sim adapters do; real-hw adapters typically + # don't until an estimator is wired). Quiet when no source. + odom: Out[PoseStamped] + # Input: Streaming joint commands for real-time control joint_command: In[JointState] @@ -166,11 +209,22 @@ class ControlCoordinator(Module): # Input: Teleop buttons for engage/disengage signaling buttons: In[Buttons] + # Input: Arm/disarm velocity-policy tasks (e.g. GrootWBCTask). True + # → task.arm(); False → task.disarm(). Routed to every task that + # duck-types an ``arm`` method (and ``disarm`` for False). + activate: In[Bool] + + # Input: Toggle dry-run on velocity-policy tasks. In dry-run the + # policy keeps computing but the coordinator forwards no command to + # the adapter — operators use this to sanity-check commands on real + # hardware before committing motor torques. + dry_run: In[Bool] + def __init__(self, *args: Any, **kwargs: Any) -> None: super().__init__(*args, **kwargs) # Connected hardware (keyed by hardware_id) - self._hardware: dict[HardwareId, ConnectedHardware] = {} + self._hardware: dict[HardwareId, ConnectedHardware | ConnectedWholeBody] = {} self._hardware_lock = threading.Lock() # Joint -> hardware mapping (built when hardware added) @@ -188,6 +242,8 @@ def __init__(self, *args: Any, **kwargs: Any) -> None: self._cartesian_command_unsub: Callable[[], None] | None = None self._twist_command_unsub: Callable[[], None] | None = None self._buttons_unsub: Callable[[], None] | None = None + self._activate_unsub: Callable[[], None] | None = None + self._dry_run_unsub: Callable[[], None] | None = None logger.info(f"ControlCoordinator initialized at {self.config.tick_rate}Hz") @@ -203,6 +259,10 @@ def _setup_from_config(self) -> None: for task_cfg in self.config.tasks: task = self._create_task_from_config(task_cfg) self.add_task(task) + if task_cfg.auto_start: + start = getattr(task, "start", None) + if callable(start): + start() except Exception: # Rollback: clean up all successfully added hardware @@ -283,6 +343,28 @@ def _create_whole_body_adapter(self, component: HardwareComponent) -> WholeBodyA **component.adapter_kwargs, ) + def _create_whole_body_adapter(self, component: HardwareComponent) -> object: + """Create a whole-body adapter from component config.""" + from dimos.hardware.whole_body.registry import whole_body_adapter_registry + + # ``address`` is overloaded: real-hw adapters use it as the DDS + # network interface (string like "enp60s0" or int). Sim adapters + # use it as the MJCF path (string). Pass it raw under both names + # so each adapter can pick whichever is meaningful. + addr = component.address + net_iface: int | str = 0 + if addr is not None: + try: + net_iface = int(addr) + except ValueError: + net_iface = addr + return whole_body_adapter_registry.create( + component.adapter_type, + network_interface=net_iface, + domain_id=component.domain_id, + address=addr, + ) + def _create_task_from_config(self, cfg: TaskConfig) -> ControlTask: """Create a control task from config.""" task_type = cfg.type.lower() @@ -304,12 +386,18 @@ def _create_task_from_config(self, cfg: TaskConfig) -> ControlTask: elif task_type == "servo": from dimos.control.tasks.servo_task import JointServoTask, JointServoTaskConfig + servo_cfg_kwargs: dict[str, object] = { + "joint_names": cfg.joint_names, + "priority": cfg.priority, + } + if cfg.default_positions is not None: + servo_cfg_kwargs["default_positions"] = cfg.default_positions + # Zero timeout pairs naturally with default-hold — otherwise + # the task times out even though it's holding a valid target. + servo_cfg_kwargs["timeout"] = 0.0 return JointServoTask( cfg.name, - JointServoTaskConfig( - joint_names=cfg.joint_names, - priority=cfg.priority, - ), + JointServoTaskConfig(**servo_cfg_kwargs), # type: ignore[arg-type] ) elif task_type == "velocity": @@ -359,6 +447,46 @@ def _create_task_from_config(self, cfg: TaskConfig) -> ControlTask: ), ) + elif task_type == "groot_wbc": + from dimos.control.tasks.groot_wbc_task import ( + GrootWBCTask, + GrootWBCTaskConfig, + ) + + if cfg.model_path is None: + raise ValueError( + f"GrootWBCTask '{cfg.name}' requires model_path " + f"(directory containing balance.onnx + walk.onnx)" + ) + if cfg.hardware_id is None: + raise ValueError(f"GrootWBCTask '{cfg.name}' requires hardware_id in TaskConfig") + hw = self._hardware.get(cfg.hardware_id) + if hw is None: + raise ValueError( + f"GrootWBCTask '{cfg.name}' references unknown hardware " + f"'{cfg.hardware_id}'. List the hardware before the task " + f"in the blueprint config." + ) + + model_dir = Path(cfg.model_path) + wbc_kwargs: dict[str, Any] = dict( + balance_onnx=model_dir / "balance.onnx", + walk_onnx=model_dir / "walk.onnx", + joint_names=cfg.joint_names, + all_joint_names=hw.joint_names, + priority=cfg.priority, + auto_arm=cfg.auto_arm, + auto_dry_run=cfg.auto_dry_run, + default_ramp_seconds=cfg.default_ramp_seconds, + ) + if cfg.decimation is not None: + wbc_kwargs["decimation"] = cfg.decimation + return GrootWBCTask( + cfg.name, + GrootWBCTaskConfig(**wbc_kwargs), + adapter=hw.adapter, + ) + else: raise ValueError(f"Unknown task type: {task_type}") @@ -594,12 +722,52 @@ def _on_twist_command(self, msg: Twist) -> None: joint_state = JointState(name=names, velocity=velocities) self._on_joint_command(joint_state) + # Also route to tasks that accept a (vx, vy, yaw_rate) command — + # e.g. locomotion policies like GrootWBCTask. Duck-typed: any + # task exposing set_velocity_command opts in. + t_now = time.perf_counter() + with self._task_lock: + for task in self._tasks.values(): + set_vel = getattr(task, "set_velocity_command", None) + if set_vel is not None: + set_vel(msg.linear.x, msg.linear.y, msg.angular.z, t_now) + def _on_buttons(self, msg: Buttons) -> None: """Forward button state to all tasks.""" with self._task_lock: for task in self._tasks.values(): task.on_buttons(msg) + def _on_activate(self, msg: Bool) -> None: + """Arm/disarm every task exposing ``arm()`` / ``disarm()``. + + Duck-typed to match the ``set_velocity_command`` convention used + by ``_on_twist_command``. The blueprint wires this input to a + dashboard button; operators can also drive it directly via LCM. + """ + engage = bool(msg.data) + with self._task_lock: + for task in self._tasks.values(): + method_name = "arm" if engage else "disarm" + handler = getattr(task, method_name, None) + if callable(handler): + try: + handler() + except Exception: + logger.exception(f"{method_name}() raised on task {task.name!r}") + + def _on_dry_run(self, msg: Bool) -> None: + """Forward dry-run toggle to every task exposing ``set_dry_run``.""" + enabled = bool(msg.data) + with self._task_lock: + for task in self._tasks.values(): + handler = getattr(task, "set_dry_run", None) + if callable(handler): + try: + handler(enabled) + except Exception: + logger.exception(f"set_dry_run() raised on task {task.name!r}") + @rpc def task_invoke( self, task_name: TaskName, method: str, kwargs: dict[str, Any] | None = None @@ -671,6 +839,7 @@ def start(self) -> None: # Create and start tick loop publish_cb = self.joint_state.publish if self.config.publish_joint_state else None + odom_cb = self.odom.publish if self.config.publish_odom else None self._tick_loop = TickLoop( tick_rate=self.config.tick_rate, hardware=self._hardware, @@ -679,6 +848,7 @@ def start(self) -> None: task_lock=self._task_lock, joint_to_hardware=self._joint_to_hardware, publish_callback=publish_cb, + odom_callback=odom_cb, frame_id=self.config.joint_state_frame_id, log_ticks=self.config.log_ticks, ) @@ -711,16 +881,25 @@ def start(self) -> None: "Use task_invoke RPC or set transport via blueprint." ) - # Subscribe to twist commands if any twist base hardware configured + # Subscribe to twist commands if any twist base hardware is configured + # OR if any task accepts velocity commands (locomotion policies like + # GrootWBCTask duck-type with set_velocity_command). Without the + # latter check, a whole-body locomotion blueprint with no BASE + # hardware silently drops every Twist on /cmd_vel. has_twist_base = any(c.hardware_type == HardwareType.BASE for c in self.config.hardware) - if has_twist_base: + with self._task_lock: + has_velocity_task = any( + callable(getattr(task, "set_velocity_command", None)) + for task in self._tasks.values() + ) + if has_twist_base or has_velocity_task: try: self._twist_command_unsub = self.twist_command.subscribe(self._on_twist_command) - logger.info("Subscribed to twist_command for twist base control") + logger.info("Subscribed to twist_command for twist base / velocity-capable tasks") except Exception: logger.warning( - "Twist base configured but could not subscribe to twist_command. " - "Use task_invoke RPC or set transport via blueprint." + "Twist base or velocity-capable task configured but could not subscribe " + "to twist_command. Use task_invoke RPC or set transport via blueprint." ) # Subscribe to buttons if any teleop_ik tasks configured (engage/disengage) @@ -729,6 +908,32 @@ def start(self) -> None: self._buttons_unsub = self.buttons.subscribe(self._on_buttons) logger.info("Subscribed to buttons for engage/disengage") + # Subscribe to activate / dry_run if any task exposes arm() / set_dry_run() + # (duck-typed, same convention as twist_command / set_velocity_command). + with self._task_lock: + has_arm = any(callable(getattr(t, "arm", None)) for t in self._tasks.values()) + has_dry_run = any( + callable(getattr(t, "set_dry_run", None)) for t in self._tasks.values() + ) + if has_arm: + try: + self._activate_unsub = self.activate.subscribe(self._on_activate) + logger.info("Subscribed to activate for arm()/disarm() routing") + except Exception: + logger.warning( + "Arm-capable task configured but could not subscribe to activate. " + "Use task_invoke RPC or set transport via blueprint." + ) + if has_dry_run: + try: + self._dry_run_unsub = self.dry_run.subscribe(self._on_dry_run) + logger.info("Subscribed to dry_run for dry-run routing") + except Exception: + logger.warning( + "Dry-run-capable task configured but could not subscribe to dry_run. " + "Use task_invoke RPC or set transport via blueprint." + ) + logger.info(f"ControlCoordinator started at {self.config.tick_rate}Hz") @rpc @@ -746,6 +951,12 @@ def stop(self) -> None: if self._twist_command_unsub: self._twist_command_unsub() self._twist_command_unsub = None + if self._activate_unsub: + self._activate_unsub() + self._activate_unsub = None + if self._dry_run_unsub: + self._dry_run_unsub() + self._dry_run_unsub = None if self._buttons_unsub: self._buttons_unsub() self._buttons_unsub = None diff --git a/dimos/control/hardware_interface.py b/dimos/control/hardware_interface.py index 0169321600..ae590e7802 100644 --- a/dimos/control/hardware_interface.py +++ b/dimos/control/hardware_interface.py @@ -332,6 +332,34 @@ def __init__( self._component = component self._joint_names = component.joints + # Resolve per-joint PD gains once at wire-up time. Gains live on + # the WB-specific sub-config; fall back to _DEFAULT_KP/_DEFAULT_KD + # if the blueprint didn't supply a wb_config. + n = len(self._joint_names) + wb = component.wb_config + kp_in = wb.kp if wb is not None else None + kd_in = wb.kd if wb is not None else None + if kp_in is not None: + if len(kp_in) != n: + raise ValueError( + f"HardwareComponent '{component.hardware_id}': wb_config.kp length " + f"{len(kp_in)} does not match joints length {n}" + ) + self._kp = list(kp_in) + else: + self._kp = [_DEFAULT_KP] * n + if kd_in is not None: + if len(kd_in) != n: + raise ValueError( + f"HardwareComponent '{component.hardware_id}': wb_config.kd length " + f"{len(kd_in)} does not match joints length {n}" + ) + self._kd = list(kd_in) + else: + self._kd = [_DEFAULT_KD] * n + self._kp_by_name = dict(zip(self._joint_names, self._kp, strict=False)) + self._kd_by_name = dict(zip(self._joint_names, self._kd, strict=False)) + self._last_commanded: dict[str, float] = {} self._initialized = False self._warned_unknown_joints: set[str] = set() @@ -361,10 +389,13 @@ def read_state(self) -> dict[JointName, JointState]: } def write_command(self, commands: dict[str, float], mode: ControlMode) -> bool: - """Write position commands — converts to MotorCommand with PD gains. + """Write position commands — converts to MotorCommand with per-joint PD gains. Only POSITION / SERVO_POSITION are supported; other modes are warned and dropped (matches ConnectedHardware's warn-and-skip pattern). + Per-joint kp/kd come from ``component.wb_config`` (resolved in + ``__init__``); fall back to ``_DEFAULT_KP``/``_DEFAULT_KD`` when + the blueprint didn't supply gains. """ from dimos.hardware.whole_body.spec import MotorCommand @@ -392,8 +423,8 @@ def write_command(self, commands: dict[str, float], mode: ControlMode) -> bool: MotorCommand( q=self._last_commanded[name], dq=0.0, - kp=_DEFAULT_KP, - kd=_DEFAULT_KD, + kp=self._kp_by_name[name], + kd=self._kd_by_name[name], tau=0.0, ) for name in self._joint_names diff --git a/dimos/control/tasks/groot_wbc_task.py b/dimos/control/tasks/groot_wbc_task.py new file mode 100644 index 0000000000..5a321b9ddf --- /dev/null +++ b/dimos/control/tasks/groot_wbc_task.py @@ -0,0 +1,642 @@ +# 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. + +"""GR00T whole-body-control task for the Unitree G1 humanoid. + +Runs the two-model GR00T WBC locomotion policy (balance + walk) inside +the coordinator tick loop. Claims the 15 legs+waist joints at high +priority; arm joints are left to lower-priority tasks in the blueprint. + +Reference implementation: g1_control/backends/groot_wbc_backend.py. +Observation, action, and model-selection semantics are preserved +verbatim — changing them drifts us away from the ONNX policies trained +by GR00T-WholeBodyControl. + +CRITICAL: Uses t_now from CoordinatorState, never calls time.time(). +""" + +from __future__ import annotations + +from dataclasses import dataclass, field +import threading +from typing import TYPE_CHECKING + +import numpy as np +import onnxruntime as ort # type: ignore[import-untyped] + +from dimos.control.task import ( + BaseControlTask, + ControlMode, + CoordinatorState, + JointCommandOutput, + ResourceClaim, +) +from dimos.utils.logging_config import setup_logger + +if TYPE_CHECKING: + from pathlib import Path + + from dimos.hardware.whole_body.spec import WholeBodyAdapter + from dimos.msgs.geometry_msgs import Twist + +logger = setup_logger() + + +# Default joint angles copied verbatim from +# g1_control/backends/groot_wbc_backend.py DEFAULT_29. Policy was trained +# against these as the zero-offset pose. +_DEFAULT_POSITIONS_29 = [ + -0.1, + 0.0, + 0.0, + 0.3, + -0.2, + 0.0, # left leg + -0.1, + 0.0, + 0.0, + 0.3, + -0.2, + 0.0, # right leg + 0.0, + 0.0, + 0.0, # waist + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, # left arm (not driven by policy) + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, + 0.0, # right arm (not driven by policy) +] + +_SINGLE_OBS_DIM = 86 +_OBS_HISTORY_LEN = 6 +_NUM_ACTIONS = 15 +_NUM_MOTORS = 29 + + +@dataclass +class GrootWBCTaskConfig: + """Configuration for the GR00T WBC task. + + Attributes: + balance_onnx: Path to the balance ONNX model. Used when + ``||cmd|| <= cmd_norm_threshold``. + walk_onnx: Path to the walk ONNX model. Used otherwise. + joint_names: The 15 coordinator joint names this task claims + (legs 0-11 + waist 12-14, in DDS order). + all_joint_names: All 29 coordinator joint names in DDS order + (legs 0-11 + waist 12-14 + arms 15-28). Required to build + the observation, which feeds all 29 joint states. + default_positions_29: Default joint angles for all 29 joints + (DDS order). First 15 are the policy's zero-offset pose. + priority: Arbitration priority (higher wins). 50 is the + recommended WBC priority per the task.py conventions. + decimation: Run inference every N ticks. At 500 Hz tick / + 50 Hz policy → decimation=10. + action_scale: Multiplier on raw policy output before adding + defaults. + obs_ang_vel_scale: Scale for base angular velocity in obs. + obs_dof_pos_scale: Scale for joint position offset in obs. + obs_dof_vel_scale: Scale for joint velocity in obs. + cmd_scale: Per-axis scale applied to (vx, vy, wz) in obs. + cmd_norm_threshold: ||cmd|| below this selects the balance + model, otherwise walk. + height_cmd: Fixed height command slot in obs. + timeout: Seconds without a velocity command before zeroing it. + auto_arm: Arm the policy automatically on ``start()``. Default + False — safe for real hardware; the blueprint sets True for + simulation. + auto_dry_run: Enter dry-run mode on ``start()``. Policy still + runs but outputs are not emitted to the adapter — useful for + verifying on real hardware without commanding motors. + default_ramp_seconds: Duration of the arming ramp (current pose + → ``default_15``) when ``arm()`` is called without an + explicit duration. Set to 0 in simulation (no ramp needed); + 10 s on real hardware mirrors the g1-control-api default. + """ + + balance_onnx: str | Path + walk_onnx: str | Path + joint_names: list[str] + all_joint_names: list[str] + default_positions_29: list[float] = field(default_factory=lambda: list(_DEFAULT_POSITIONS_29)) + priority: int = 50 + decimation: int = 10 + action_scale: float = 0.25 + obs_ang_vel_scale: float = 0.5 + obs_dof_pos_scale: float = 1.0 + obs_dof_vel_scale: float = 0.05 + cmd_scale: tuple[float, float, float] = (2.0, 2.0, 0.5) + cmd_norm_threshold: float = 0.05 + height_cmd: float = 0.74 + timeout: float = 1.0 + auto_arm: bool = False + auto_dry_run: bool = False + default_ramp_seconds: float = 10.0 + + +class GrootWBCTask(BaseControlTask): + """Runs the GR00T balance / walk ONNX policies inside the coordinator tick loop. + + Observation vector (86 dims, built each inference tick, replicates + ``groot_wbc_backend.GrootWBCBackend._compute_obs`` verbatim): + + [0:3] cmd_vel * cmd_scale # scaled velocity command + [3] height_cmd # fixed slot (0.74) + [4:7] (0, 0, 0) # rpy_cmd, zeros + [7:10] gyro * obs_ang_vel_scale # body-frame ang vel + [10:13] projected_gravity(quat) # gravity in body frame + [13:42] (q_29 - default_29) * dof_pos_scale + [42:71] dq_29 * dof_vel_scale + [71:86] last_action (15 dims) + + The observation is stacked into a 6-frame history buffer (516 dims) + before being fed to ONNX. + + Action (15 dims, legs + waist only): + + target_q_15 = action * action_scale + default_15 + + Arms are NOT driven by this task — the blueprint pairs this task + with a lower-priority servo task scoped to the 14 arm joints. + """ + + def __init__( + self, + name: str, + config: GrootWBCTaskConfig, + adapter: WholeBodyAdapter, + ) -> None: + if len(config.joint_names) != _NUM_ACTIONS: + raise ValueError( + f"GrootWBCTask '{name}' requires exactly {_NUM_ACTIONS} joint names " + f"(legs + waist), got {len(config.joint_names)}" + ) + if len(config.all_joint_names) != _NUM_MOTORS: + raise ValueError( + f"GrootWBCTask '{name}' requires exactly {_NUM_MOTORS} all_joint_names " + f"(full 29-DOF G1), got {len(config.all_joint_names)}" + ) + if len(config.default_positions_29) != _NUM_MOTORS: + raise ValueError( + f"GrootWBCTask '{name}' requires exactly {_NUM_MOTORS} " + f"default_positions_29, got {len(config.default_positions_29)}" + ) + if config.decimation < 1: + raise ValueError(f"GrootWBCTask '{name}' requires decimation >= 1") + + self._name = name + self._config = config + self._adapter = adapter + self._joint_names_list = list(config.joint_names) + self._joint_names_set = frozenset(config.joint_names) + self._all_joint_names = list(config.all_joint_names) + + providers = ort.get_available_providers() + self._balance_session = ort.InferenceSession(str(config.balance_onnx), providers=providers) + self._walk_session = ort.InferenceSession(str(config.walk_onnx), providers=providers) + self._balance_input = self._balance_session.get_inputs()[0].name + self._walk_input = self._walk_session.get_inputs()[0].name + logger.info( + f"GrootWBCTask '{name}' loaded balance={config.balance_onnx}, " + f"walk={config.walk_onnx} (providers: {providers})" + ) + + self._default_29 = np.asarray(config.default_positions_29, dtype=np.float32) + self._default_15 = self._default_29[:_NUM_ACTIONS] + self._cmd_scale = np.asarray(config.cmd_scale, dtype=np.float32) + + # Inference state + self._last_action = np.zeros(_NUM_ACTIONS, dtype=np.float32) + self._obs_buf = np.zeros((1, _SINGLE_OBS_DIM * _OBS_HISTORY_LEN), dtype=np.float32) + self._first_inference = True + self._tick_count = 0 + self._last_targets: list[float] | None = None + + # Lifecycle state machine. + # + # _active — task is registered and compute() is being invoked + # by the coordinator. Gate for the whole compute() + # path; start()/stop() toggle this. + # _armed — policy outputs are emitted to the adapter. Flip + # via arm()/disarm(). + # _arming — currently ramping current-pose → default_15 over + # ``_arming_duration`` seconds. Set by arm() with + # a non-zero ramp, cleared when alpha reaches 1. + # _arm_pending — arm() was called; compute() captures the ramp + # start pose from state on the next tick and flips + # into _arming (or _armed directly if ramp=0). + # _dry_run — compute() still runs the policy (obs history + # stays hot) but returns None so the coordinator + # sends no command to the adapter. Throttled log + # lets the operator see what WOULD have gone out. + # + # When active-but-unarmed, compute() echoes back the current + # joint positions so the PD error is zero and the robot sits in + # pure damping (kd-only) — this mirrors the reference backend's + # "hold current pose" inactive state. + self._active = False + self._armed = False + self._arming = False + self._arm_pending = False + self._dry_run = bool(config.auto_dry_run) + self._arming_duration = 0.0 + self._arming_start_t = 0.0 + self._ramp_start: np.ndarray | None = None + self._last_dry_run_log_t: float = 0.0 + + self._cmd_lock = threading.Lock() + self._cmd = np.zeros(3, dtype=np.float32) + self._last_cmd_time: float = 0.0 + + @property + def name(self) -> str: + return self._name + + def claim(self) -> ResourceClaim: + return ResourceClaim( + joints=self._joint_names_set, + priority=self._config.priority, + mode=ControlMode.SERVO_POSITION, + ) + + def is_active(self) -> bool: + return self._active + + def compute(self, state: CoordinatorState) -> JointCommandOutput | None: + if not self._active: + return None + + # Read our 15 claimed joints' current positions — needed for the + # hold-pose / ramp-start / unarmed echo paths below. + current_15 = np.zeros(_NUM_ACTIONS, dtype=np.float32) + for i, jname in enumerate(self._joint_names_list): + pos = state.joints.get_position(jname) + current_15[i] = pos if pos is not None else 0.0 + + # ------------------------------------------------------------------ + # arm() was called — snapshot the ramp start and enter arming / + # armed state (ramp=0 arms immediately). + # ------------------------------------------------------------------ + if self._arm_pending: + self._ramp_start = current_15.copy() + self._arming_start_t = state.t_now + if self._arming_duration > 0.0: + self._arming = True + self._armed = False + logger.info( + f"GrootWBCTask '{self._name}' arming: " + f"ramp → default_15 over {self._arming_duration:.1f}s" + ) + else: + self._arming = False + self._armed = True + self._reset_policy_state() + logger.info(f"GrootWBCTask '{self._name}' armed (no ramp)") + self._arm_pending = False + + # ------------------------------------------------------------------ + # Unarmed & not arming: echo current joint positions. With the + # component's kp/kd applied downstream, q_tgt == q_actual yields + # pure damping (tau = -kd * dq), which mirrors the reference + # backend's inactive "hold current pose" behaviour. + # ------------------------------------------------------------------ + if not self._armed and not self._arming: + self._last_targets = current_15.tolist() + return JointCommandOutput( + joint_names=self._joint_names_list, + positions=self._last_targets, + mode=ControlMode.SERVO_POSITION, + ) + + # ------------------------------------------------------------------ + # Arming: lerp ramp_start → default_15 over arming_duration. + # ------------------------------------------------------------------ + if self._arming: + assert self._ramp_start is not None + elapsed = state.t_now - self._arming_start_t + alpha = ( + 1.0 if self._arming_duration <= 0.0 else min(1.0, elapsed / self._arming_duration) + ) + target = self._ramp_start + alpha * (self._default_15 - self._ramp_start) + self._last_targets = target.tolist() + if alpha >= 1.0: + self._arming = False + self._armed = True + self._reset_policy_state() + logger.info( + f"GrootWBCTask '{self._name}' ramp complete — policy armed " + f"({'dry-run' if self._dry_run else 'live'})" + ) + return JointCommandOutput( + joint_names=self._joint_names_list, + positions=self._last_targets, + mode=ControlMode.SERVO_POSITION, + ) + + # ------------------------------------------------------------------ + # Armed: run the policy. In dry-run mode we still compute (so + # the obs buffer stays hot), but return None so no command goes + # downstream. A throttled log line shows what WOULD have been + # sent, which is how g1-control-api lets operators verify pre-go. + # ------------------------------------------------------------------ + self._tick_count += 1 + + # Decimation: only run inference every N ticks. Between inference + # ticks, re-emit the last target so the coordinator keeps driving + # the joints (or nothing, in dry-run). + if self._tick_count % self._config.decimation != 0: + if self._dry_run or self._last_targets is None: + return None + return JointCommandOutput( + joint_names=self._joint_names_list, + positions=self._last_targets, + mode=ControlMode.SERVO_POSITION, + ) + + # Read all 29 joints from CoordinatorState in DDS order. + q_29 = np.zeros(_NUM_MOTORS, dtype=np.float32) + dq_29 = np.zeros(_NUM_MOTORS, dtype=np.float32) + for i, jname in enumerate(self._all_joint_names): + pos = state.joints.get_position(jname) + vel = state.joints.get_velocity(jname) + q_29[i] = pos if pos is not None else 0.0 + dq_29[i] = vel if vel is not None else 0.0 + + # IMU comes from the adapter, not CoordinatorState. + imu = self._adapter.read_imu() + gyro = np.asarray(imu.gyroscope, dtype=np.float32) + gravity = self._projected_gravity(imu.quaternion) + + # Velocity command (with timeout → zero). + with self._cmd_lock: + if ( + self._config.timeout > 0.0 + and self._last_cmd_time > 0.0 + and (state.t_now - self._last_cmd_time) > self._config.timeout + ): + cmd = np.zeros(3, dtype=np.float32) + else: + cmd = self._cmd.copy() + + obs = self._build_obs(cmd=cmd, gyro=gyro, gravity=gravity, q=q_29, dq=dq_29) + + # History buffer: first inference fills all slots with the current + # obs (warm-start); subsequent ticks roll the window. + if self._first_inference: + tiled = np.tile(obs, _OBS_HISTORY_LEN) + self._obs_buf[0, :] = tiled + self._first_inference = False + else: + self._obs_buf[0, : _SINGLE_OBS_DIM * (_OBS_HISTORY_LEN - 1)] = self._obs_buf[ + 0, _SINGLE_OBS_DIM: + ] + self._obs_buf[0, _SINGLE_OBS_DIM * (_OBS_HISTORY_LEN - 1) :] = obs + + # Model selection: balance when near-stationary, walk otherwise. + cmd_norm = float(np.linalg.norm(cmd)) + if cmd_norm <= self._config.cmd_norm_threshold: + raw = self._balance_session.run(None, {self._balance_input: self._obs_buf})[0] + else: + raw = self._walk_session.run(None, {self._walk_input: self._obs_buf})[0] + + action = raw[0, :_NUM_ACTIONS].astype(np.float32) + self._last_action[:] = action + + target_q_15 = action * self._config.action_scale + self._default_15 + self._last_targets = target_q_15.tolist() + + if self._dry_run: + # Throttled peek at the commanded pose so the operator can + # decide whether it looks sane before flipping dry-run off. + if (state.t_now - self._last_dry_run_log_t) >= 1.0: + max_delta = float(np.max(np.abs(target_q_15 - current_15))) + logger.info( + f"GrootWBCTask '{self._name}' DRY-RUN (|Δq|_max={max_delta:.3f} rad, " + f"model={'walk' if cmd_norm > self._config.cmd_norm_threshold else 'balance'})" + ) + self._last_dry_run_log_t = state.t_now + return None + + return JointCommandOutput( + joint_names=self._joint_names_list, + positions=self._last_targets, + mode=ControlMode.SERVO_POSITION, + ) + + def on_preempted(self, by_task: str, joints: frozenset[str]) -> None: + if joints & self._joint_names_set: + logger.warning(f"GrootWBCTask '{self._name}' preempted by {by_task} on {joints}") + + # ------------------------------------------------------------------ + # Velocity command input + # ------------------------------------------------------------------ + + def set_velocity_command(self, vx: float, vy: float, yaw_rate: float, t_now: float) -> None: + """Set the (vx, vy, yaw_rate) commanded to the policy. + + Called by the coordinator's twist_command dispatcher and by + external Python callers. Thread-safe. + """ + with self._cmd_lock: + self._cmd[:] = [vx, vy, yaw_rate] + self._last_cmd_time = t_now + + def on_twist(self, msg: Twist, t_now: float) -> bool: + """Accept a Twist message, e.g. from an LCM cmd_vel transport.""" + self.set_velocity_command( + float(msg.linear.x), + float(msg.linear.y), + float(msg.angular.z), + t_now, + ) + return True + + # ------------------------------------------------------------------ + # Lifecycle + # ------------------------------------------------------------------ + + def start(self) -> None: + """Enter the coordinator tick loop. + + Starts in "active but unarmed" — compute() echoes current joint + positions every tick, which (combined with the component's + kp/kd) produces damping-only behaviour on real hardware (the + robot sits quietly in dev mode). + + If ``config.auto_arm`` is set, schedules an immediate + ``arm()`` using ``config.default_ramp_seconds`` — this is how + the simulation blueprint bypasses the activation ritual. + If ``config.auto_dry_run`` is set, starts in dry-run mode. + """ + self._active = True + self._armed = False + self._arming = False + self._arm_pending = False + self._dry_run = bool(self._config.auto_dry_run) + self._last_targets = None + self._reset_policy_state() + with self._cmd_lock: + self._cmd[:] = 0.0 + self._last_cmd_time = 0.0 + logger.info( + f"GrootWBCTask '{self._name}' started (unarmed" + + (", dry-run" if self._dry_run else "") + + ")" + ) + if self._config.auto_arm: + self.arm(self._config.default_ramp_seconds) + + def stop(self) -> None: + """Leave the tick loop. Re-activation resets policy state.""" + self._active = False + self._armed = False + self._arming = False + self._arm_pending = False + self._last_targets = None + logger.info(f"GrootWBCTask '{self._name}' stopped") + + # ------------------------------------------------------------------ + # Arming / dry-run (RPC-callable via coordinator.task_invoke) + # ------------------------------------------------------------------ + + def arm(self, ramp_seconds: float | None = None) -> bool: + """Begin the arming sequence. + + ``compute()`` will snapshot the current joint positions on the + next tick, lerp toward ``default_15`` over ``ramp_seconds``, + then flip ``_armed`` true and hand control to the ONNX policy. + A ramp of 0 arms immediately with no interpolation (what sim + uses — the subprocess already holds the MJCF's default pose). + + Safe to call redundantly; subsequent calls while already armed + are ignored. No-op if the task is not ``_active``. + """ + if not self._active: + logger.warning(f"GrootWBCTask '{self._name}' arm() called before start() — ignoring") + return False + if self._armed: + logger.info(f"GrootWBCTask '{self._name}' already armed — arm() ignored") + return False + ramp = ramp_seconds if ramp_seconds is not None else self._config.default_ramp_seconds + self._arming_duration = max(0.0, float(ramp)) + self._arm_pending = True + logger.info( + f"GrootWBCTask '{self._name}' arm requested (ramp={self._arming_duration:.1f}s)" + ) + return True + + def disarm(self) -> bool: + """Stop emitting policy outputs; fall back to hold-current-pose. + + Called either from an operator ``Disarm`` button or from + safety watchdogs. Resets obs history so the next ``arm()`` + starts with a clean buffer. + """ + if not self._armed and not self._arming and not self._arm_pending: + return False + self._armed = False + self._arming = False + self._arm_pending = False + self._ramp_start = None + self._reset_policy_state() + logger.info(f"GrootWBCTask '{self._name}' disarmed (holding current pose)") + return True + + def set_dry_run(self, enabled: bool) -> None: + """Enable/disable dry-run. + + In dry-run the policy still runs (obs history stays hot) but + ``compute()`` returns ``None``, so the coordinator forwards no + command to the adapter. Use to verify policy sanity on real + hardware before committing motor torques. + """ + new_val = bool(enabled) + if new_val == self._dry_run: + return + self._dry_run = new_val + self._last_dry_run_log_t = 0.0 + logger.info(f"GrootWBCTask '{self._name}' dry_run = {new_val}") + + def state_snapshot(self) -> dict[str, object]: + """Return the current state-machine flags for UI / telemetry.""" + return { + "active": self._active, + "armed": self._armed, + "arming": self._arming, + "arm_pending": self._arm_pending, + "dry_run": self._dry_run, + "arming_duration": self._arming_duration, + } + + # ------------------------------------------------------------------ + # Internal helpers + # ------------------------------------------------------------------ + + def _reset_policy_state(self) -> None: + """Clear inference state — obs history, last action, tick count.""" + self._last_action[:] = 0.0 + self._obs_buf[:] = 0.0 + self._first_inference = True + self._tick_count = 0 + + def _build_obs( + self, + cmd: np.ndarray, + gyro: np.ndarray, + gravity: np.ndarray, + q: np.ndarray, + dq: np.ndarray, + ) -> np.ndarray: + """Build the 86-dim GR00T observation. Layout matches + ``groot_wbc_backend.py`` exactly.""" + obs = np.zeros(_SINGLE_OBS_DIM, dtype=np.float32) + obs[0:3] = cmd * self._cmd_scale + obs[3] = self._config.height_cmd + obs[4:7] = 0.0 + obs[7:10] = gyro * self._config.obs_ang_vel_scale + obs[10:13] = gravity + obs[13:42] = (q - self._default_29) * self._config.obs_dof_pos_scale + obs[42:71] = dq * self._config.obs_dof_vel_scale + obs[71:86] = self._last_action + return obs + + @staticmethod + def _projected_gravity(quaternion: tuple[float, ...]) -> np.ndarray: + """Project world gravity into body frame. + + Uses Unitree DDS quaternion order (w, x, y, z). Formula matches + ``groot_wbc_backend._get_gravity_orientation`` and is + algebraically equivalent to the Go2 RLPolicyTask helper. + """ + w, x, y, z = quaternion + gx = 2.0 * (-x * z + w * y) + gy = 2.0 * (-y * z - w * x) + gz = -(w * w - x * x - y * y + z * z) + return np.array([gx, gy, gz], dtype=np.float32) + + +__all__ = [ + "GrootWBCTask", + "GrootWBCTaskConfig", +] diff --git a/dimos/control/tasks/servo_task.py b/dimos/control/tasks/servo_task.py index ac83a16244..0ffe06b216 100644 --- a/dimos/control/tasks/servo_task.py +++ b/dimos/control/tasks/servo_task.py @@ -46,11 +46,17 @@ class JointServoTaskConfig: joint_names: List of joint names this task controls priority: Priority for arbitration (higher wins) timeout: If no command received for this many seconds, go inactive (0 = never timeout) + default_positions: Optional initial target held until/unless a + new target arrives via set_target(). Must match joint_names + length if provided. Useful for "hold at this pose" tasks + (e.g. arms during whole-body locomotion). Pair with + timeout=0.0 to hold indefinitely. """ joint_names: list[str] priority: int = 10 timeout: float = 0.5 # 500ms default timeout + default_positions: list[float] | None = None class JointServoTask(BaseControlTask): @@ -99,6 +105,15 @@ def __init__(self, name: str, config: JointServoTaskConfig) -> None: self._last_update_time: float = 0.0 self._active = False + if config.default_positions is not None: + if len(config.default_positions) != self._num_joints: + raise ValueError( + f"JointServoTask '{name}': default_positions length " + f"{len(config.default_positions)} does not match " + f"joint_names length {self._num_joints}" + ) + self._target = list(config.default_positions) + logger.info(f"JointServoTask {name} initialized for joints: {config.joint_names}") @property diff --git a/dimos/control/tasks/test_groot_wbc_task.py b/dimos/control/tasks/test_groot_wbc_task.py new file mode 100644 index 0000000000..bc6f5f9c9a --- /dev/null +++ b/dimos/control/tasks/test_groot_wbc_task.py @@ -0,0 +1,463 @@ +# 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. + +"""Unit tests for GrootWBCTask. + +ONNX runtime is monkey-patched with a stub that records which model +was called and returns a deterministic action — so the tests exercise +the obs-build, model-selection, decimation, and command-timeout logic +without depending on the actual GR00T ONNX weights. +""" + +from __future__ import annotations + +import math +from typing import Any +from unittest.mock import MagicMock + +import numpy as np +import pytest + +from dimos.control.components import make_humanoid_joints +from dimos.control.task import ( + ControlMode, + CoordinatorState, + JointStateSnapshot, +) +from dimos.control.tasks import groot_wbc_task +from dimos.control.tasks.groot_wbc_task import GrootWBCTask, GrootWBCTaskConfig +from dimos.hardware.whole_body.spec import IMUState + +# --------------------------------------------------------------------------- +# Fixtures +# --------------------------------------------------------------------------- + + +class _StubSession: + """ONNX InferenceSession stub that tracks call count and returns a fixed action.""" + + def __init__( + self, + model_path: str, + *, + label: str, + action: np.ndarray, + call_log: list[str], + ) -> None: + self.model_path = model_path + self._label = label + self._action = action + self._call_log = call_log + fake_input = MagicMock() + fake_input.name = "obs" + self._inputs = [fake_input] + + def get_inputs(self) -> list[Any]: + return self._inputs + + def run(self, _outputs: Any, _feed: dict[str, np.ndarray]) -> list[np.ndarray]: + self._call_log.append(self._label) + return [self._action.reshape(1, -1)] + + +@pytest.fixture +def patched_ort(monkeypatch): + """Patch onnxruntime so no real ONNX files are needed.""" + call_log: list[str] = [] + + def _factory(path: str, providers: Any = None) -> _StubSession: + label = "balance" if "balance" in str(path) else "walk" + return _StubSession( + str(path), + label=label, + action=np.full(15, 0.1, dtype=np.float32), + call_log=call_log, + ) + + monkeypatch.setattr(groot_wbc_task.ort, "InferenceSession", _factory) + monkeypatch.setattr( + groot_wbc_task.ort, "get_available_providers", lambda: ["CPUExecutionProvider"] + ) + return call_log + + +@pytest.fixture +def stub_adapter(): + """Stub WholeBodyAdapter returning a zeroed-out IMU (identity quat).""" + adapter = MagicMock() + adapter.read_imu.return_value = IMUState( + quaternion=(1.0, 0.0, 0.0, 0.0), # identity (w, x, y, z) + gyroscope=(0.0, 0.0, 0.0), + accelerometer=(0.0, 0.0, -9.81), + rpy=(0.0, 0.0, 0.0), + ) + return adapter + + +@pytest.fixture +def joints_29(): + return make_humanoid_joints("g1") + + +@pytest.fixture +def task(patched_ort, stub_adapter, joints_29) -> GrootWBCTask: + """Test fixture: auto-armed with no ramp so the existing policy + tests can run compute() immediately after start(). The arming/ + dry-run state-machine has its own dedicated tests below.""" + legs_waist = joints_29[:15] + return GrootWBCTask( + name="groot_wbc", + config=GrootWBCTaskConfig( + balance_onnx="/fake/balance.onnx", + walk_onnx="/fake/walk.onnx", + joint_names=legs_waist, + all_joint_names=joints_29, + priority=50, + auto_arm=True, + default_ramp_seconds=0.0, + ), + adapter=stub_adapter, + ) + + +@pytest.fixture +def unarmed_task(patched_ort, stub_adapter, joints_29) -> GrootWBCTask: + """Fixture mirroring the real-hardware blueprint: active but + unarmed on start(), so arm()/disarm()/set_dry_run() can be + exercised explicitly.""" + legs_waist = joints_29[:15] + return GrootWBCTask( + name="groot_wbc", + config=GrootWBCTaskConfig( + balance_onnx="/fake/balance.onnx", + walk_onnx="/fake/walk.onnx", + joint_names=legs_waist, + all_joint_names=joints_29, + priority=50, + auto_arm=False, + default_ramp_seconds=0.0, + ), + adapter=stub_adapter, + ) + + +def _state_at(t_now: float, joint_names: list[str]) -> CoordinatorState: + snap = JointStateSnapshot( + joint_positions={n: 0.0 for n in joint_names}, + joint_velocities={n: 0.0 for n in joint_names}, + joint_efforts={n: 0.0 for n in joint_names}, + timestamp=t_now, + ) + return CoordinatorState(joints=snap, t_now=t_now, dt=0.002) + + +# --------------------------------------------------------------------------- +# Tests +# --------------------------------------------------------------------------- + + +def test_claim_shape(task, joints_29): + claim = task.claim() + assert claim.joints == frozenset(joints_29[:15]) + assert claim.priority == 50 + assert claim.mode == ControlMode.SERVO_POSITION + + +def test_inactive_returns_none(task, joints_29): + state = _state_at(100.0, joints_29) + assert task.compute(state) is None + + +def test_active_zero_cmd_routes_to_balance(task, joints_29, patched_ort): + task.start() + # Decimation=10 → run compute 10 times to force first inference. + state = _state_at(100.0, joints_29) + result = None + for _ in range(10): + result = task.compute(state) + assert result is not None + assert len(result.positions) == 15 + assert patched_ort == ["balance"] + + +def test_nonzero_cmd_routes_to_walk(task, joints_29, patched_ort): + task.start() + task.set_velocity_command(0.5, 0.0, 0.0, t_now=100.0) + state = _state_at(100.0, joints_29) + for _ in range(10): + task.compute(state) + assert patched_ort == ["walk"] + + +def test_decimation_reemits_last_targets(task, joints_29, patched_ort): + """Between inference ticks, the task should repeat the last output.""" + task.start() + state = _state_at(100.0, joints_29) + # First 9 ticks pre-inference: no targets yet. + for _ in range(9): + assert task.compute(state) is None + # 10th tick: inference fires. + first = task.compute(state) + assert first is not None + assert len(patched_ort) == 1 + # Next 9 ticks: no inference, same targets echoed. + for _ in range(9): + echo = task.compute(state) + assert echo is not None + assert echo.positions == first.positions + assert len(patched_ort) == 1 + # 20th tick: second inference. + task.compute(state) + assert len(patched_ort) == 2 + + +def test_velocity_command_timeout(task, joints_29, patched_ort): + task.start() + task.set_velocity_command(0.5, 0.0, 0.0, t_now=100.0) + # Still inside the 1.0s timeout — walk. + state_inside = _state_at(100.5, joints_29) + for _ in range(10): + task.compute(state_inside) + # Past the timeout — command goes to zero → balance. + state_outside = _state_at(102.0, joints_29) + for _ in range(10): + task.compute(state_outside) + assert patched_ort == ["walk", "balance"] + + +def test_projected_gravity_identity_quat(): + g = GrootWBCTask._projected_gravity((1.0, 0.0, 0.0, 0.0)) + np.testing.assert_allclose(g, np.array([0.0, 0.0, -1.0]), atol=1e-6) + + +def test_projected_gravity_roll_90(): + """+90° roll around body-X: body-Y now points world-up, body-Z world-right. + World gravity (0,0,-1) expressed in body frame is (0, -1, 0).""" + s = math.sin(math.pi / 4.0) + c = math.cos(math.pi / 4.0) + g = GrootWBCTask._projected_gravity((c, s, 0.0, 0.0)) + np.testing.assert_allclose(g, np.array([0.0, -1.0, 0.0]), atol=1e-6) + + +def test_projected_gravity_pitch_90(): + """+90° pitch around body-Y: body-X now points world-down, body-Z world-forward. + World gravity (0,0,-1) expressed in body frame is (+1, 0, 0).""" + s = math.sin(math.pi / 4.0) + c = math.cos(math.pi / 4.0) + g = GrootWBCTask._projected_gravity((c, 0.0, s, 0.0)) + np.testing.assert_allclose(g, np.array([1.0, 0.0, 0.0]), atol=1e-6) + + +def test_obs_build_layout(task): + """Verify the 86-dim obs respects the documented slot layout.""" + cmd = np.array([1.0, 0.5, 0.25], dtype=np.float32) + gyro = np.array([0.1, 0.2, 0.3], dtype=np.float32) + gravity = np.array([0.0, 0.0, -1.0], dtype=np.float32) + q = np.zeros(29, dtype=np.float32) + dq = np.ones(29, dtype=np.float32) + obs = task._build_obs(cmd=cmd, gyro=gyro, gravity=gravity, q=q, dq=dq) + assert obs.shape == (86,) + np.testing.assert_allclose(obs[0:3], cmd * np.array([2.0, 2.0, 0.5])) + assert obs[3] == pytest.approx(0.74) + np.testing.assert_array_equal(obs[4:7], np.zeros(3)) + np.testing.assert_allclose(obs[7:10], gyro * 0.5) + np.testing.assert_array_equal(obs[10:13], gravity) + # q - default_29 → legs/waist get nonzero offsets from DEFAULT_15, + # arms (indices 15..28 in DEFAULT_29) are zero, so obs[28:42] == 0. + np.testing.assert_array_equal(obs[28:42], np.zeros(14)) + np.testing.assert_allclose(obs[42:71], dq * 0.05) + np.testing.assert_array_equal(obs[71:86], np.zeros(15)) + + +def test_first_inference_fills_history(task, joints_29, patched_ort): + """First inference should tile current obs across all 6 history slots.""" + task.start() + state = _state_at(100.0, joints_29) + for _ in range(10): + task.compute(state) + # History has 6 identical 86-dim slices. + buf = task._obs_buf[0] + assert buf.shape == (86 * 6,) + slice0 = buf[0:86] + for k in range(1, 6): + np.testing.assert_array_equal(buf[86 * k : 86 * (k + 1)], slice0) + + +def test_start_resets_state(task, joints_29, patched_ort): + task.start() + state = _state_at(100.0, joints_29) + for _ in range(10): + task.compute(state) + assert np.any(task._last_action != 0.0) + assert task._last_targets is not None + + task.stop() + assert task._last_targets is None + + task.start() + # After restart, tick counter is zero, last_action cleared, first-inference flag set. + assert task._tick_count == 0 + np.testing.assert_array_equal(task._last_action, np.zeros(15, dtype=np.float32)) + assert task._first_inference is True + + +def test_on_twist_routes_to_velocity_cmd(task): + msg = MagicMock() + msg.linear.x = 0.7 + msg.linear.y = -0.2 + msg.angular.z = 0.4 + task.on_twist(msg, t_now=12.34) + np.testing.assert_allclose(task._cmd, np.array([0.7, -0.2, 0.4], dtype=np.float32), atol=1e-6) + assert task._last_cmd_time == 12.34 + + +def test_joint_count_validation(patched_ort, stub_adapter, joints_29): + with pytest.raises(ValueError, match="15 joint names"): + GrootWBCTask( + name="bad", + config=GrootWBCTaskConfig( + balance_onnx="/fake/balance.onnx", + walk_onnx="/fake/walk.onnx", + joint_names=joints_29[:10], # wrong size + all_joint_names=joints_29, + ), + adapter=stub_adapter, + ) + with pytest.raises(ValueError, match="29 all_joint_names"): + GrootWBCTask( + name="bad", + config=GrootWBCTaskConfig( + balance_onnx="/fake/balance.onnx", + walk_onnx="/fake/walk.onnx", + joint_names=joints_29[:15], + all_joint_names=joints_29[:20], # wrong size + ), + adapter=stub_adapter, + ) + + +# --------------------------------------------------------------------------- +# Arming / dry-run state machine +# --------------------------------------------------------------------------- + + +def test_unarmed_holds_current_pose(unarmed_task, joints_29, patched_ort): + """Active but unarmed → compute() echoes current joint positions + every tick. Downstream PD with q_tgt == q_actual → damping only.""" + unarmed_task.start() + snap = JointStateSnapshot( + joint_positions={n: 0.0 for n in joints_29}, + joint_velocities={n: 0.0 for n in joints_29}, + joint_efforts={n: 0.0 for n in joints_29}, + timestamp=100.0, + ) + # Set some non-zero current positions for the 15 claimed joints. + for i, n in enumerate(joints_29[:15]): + snap.joint_positions[n] = 0.1 * (i + 1) + state = CoordinatorState(joints=snap, t_now=100.0, dt=0.002) + for _ in range(30): + out = unarmed_task.compute(state) + assert out is not None + # No inference while unarmed. + assert patched_ort == [] + # Output tracks current pose exactly. + np.testing.assert_allclose(out.positions, [0.1 * (i + 1) for i in range(15)], atol=1e-6) + + +def test_arm_no_ramp_goes_straight_to_policy(unarmed_task, joints_29, patched_ort): + """arm(0.0) → immediately armed → policy runs on the next decimation tick.""" + unarmed_task.start() + unarmed_task.arm(ramp_seconds=0.0) + state = _state_at(100.0, joints_29) + # First compute after arm(): snapshots ramp_start, flips armed=True (ramp=0). + unarmed_task.compute(state) + assert unarmed_task._armed + # 9 more ticks to hit decimation threshold (10th is inference). + for _ in range(9): + unarmed_task.compute(state) + assert patched_ort == ["balance"] + + +def test_arm_with_ramp_lerps_over_duration(unarmed_task, joints_29, patched_ort): + """arm(1.0) → lerp from current pose to default_15 over 1 second.""" + unarmed_task.start() + unarmed_task.arm(ramp_seconds=1.0) + # First tick: snapshot ramp_start (all zeros). + state0 = _state_at(0.0, joints_29) + out0 = unarmed_task.compute(state0) + assert out0 is not None + assert unarmed_task._arming + # alpha=0 → output == ramp_start (all zeros here). + np.testing.assert_allclose(out0.positions, [0.0] * 15, atol=1e-6) + # Halfway through: alpha=0.5. + state_mid = _state_at(0.5, joints_29) + out_mid = unarmed_task.compute(state_mid) + default_15 = list(groot_wbc_task._DEFAULT_POSITIONS_29[:15]) + expected_mid = [0.5 * d for d in default_15] + np.testing.assert_allclose(out_mid.positions, expected_mid, atol=1e-6) + # End: alpha=1 → armed flips, output == default_15. + state_end = _state_at(1.0, joints_29) + unarmed_task.compute(state_end) + assert unarmed_task._armed + assert not unarmed_task._arming + # Policy has NOT run yet — ramp completion doesn't trigger inference. + assert patched_ort == [] + + +def test_dry_run_suppresses_output_but_runs_inference(task, joints_29, patched_ort): + """Dry-run: policy still computes (obs history stays hot), but + compute() returns None so the adapter sees no command.""" + task.start() # fixture has auto_arm=True, so armed immediately + task.set_dry_run(True) + state = _state_at(100.0, joints_29) + # 10 ticks → first inference fires under the hood, but output is None. + for _ in range(10): + out = task.compute(state) + assert out is None + # Policy DID run — obs buffer is hot. + assert patched_ort == ["balance"] + + +def test_dry_run_toggle_off_resumes_output(task, joints_29, patched_ort): + """Flipping dry_run from True → False resumes normal output.""" + task.start() + task.set_dry_run(True) + state = _state_at(100.0, joints_29) + for _ in range(10): + task.compute(state) + assert patched_ort == ["balance"] # ran during dry-run + task.set_dry_run(False) + # Next inference tick: output is non-None. + for _ in range(10): + out = task.compute(state) + assert out is not None + assert len(out.positions) == 15 + + +def test_disarm_returns_to_hold_pose(unarmed_task, joints_29, patched_ort): + """Disarm after policy has run → compute() falls back to echoing pose.""" + unarmed_task.start() + unarmed_task.arm(ramp_seconds=0.0) + state = _state_at(100.0, joints_29) + for _ in range(10): + unarmed_task.compute(state) + assert patched_ort == ["balance"] + assert unarmed_task._armed + + unarmed_task.disarm() + assert not unarmed_task._armed + # Policy should NOT run again. + for _ in range(30): + unarmed_task.compute(state) + assert patched_ort == ["balance"] # still just one call diff --git a/dimos/control/tick_loop.py b/dimos/control/tick_loop.py index b06cc8a5d4..4d5a25ced3 100644 --- a/dimos/control/tick_loop.py +++ b/dimos/control/tick_loop.py @@ -48,6 +48,7 @@ from dimos.control.components import HardwareId, JointName, TaskName from dimos.control.hardware_interface import ConnectedHardware from dimos.hardware.manipulators.spec import ControlMode + from dimos.msgs.geometry_msgs import PoseStamped logger = setup_logger() @@ -94,6 +95,7 @@ def __init__( task_lock: threading.Lock, joint_to_hardware: dict[JointName, HardwareId], publish_callback: Callable[[JointState], None] | None = None, + odom_callback: Callable[[PoseStamped], None] | None = None, frame_id: str = "coordinator", log_ticks: bool = False, ) -> None: @@ -104,6 +106,7 @@ def __init__( self._task_lock = task_lock self._joint_to_hardware = joint_to_hardware self._publish_callback = publish_callback + self._odom_callback = odom_callback self._frame_id = frame_id self._log_ticks = log_ticks @@ -188,6 +191,8 @@ def _tick(self) -> None: if self._publish_callback: self._publish_joint_state(joint_states) + if self._odom_callback: + self._publish_odom() # Optional logging if self._log_ticks: @@ -390,5 +395,31 @@ def _publish_joint_state(self, snapshot: JointStateSnapshot) -> None: if self._publish_callback: self._publish_callback(msg) + def _publish_odom(self) -> None: + """Poll WholeBodyAdapter.read_odom() across hardware, publish first hit. + + Multi-base-pose semantics are unspecified, and no current + blueprint runs more than one whole-body adapter; first non-None + wins so single-humanoid setups Just Work. Adapters that don't + implement ``read_odom`` (older third-party ones) are skipped. + """ + if not self._odom_callback: + return + with self._hardware_lock: + hardware_items = list(self._hardware.values()) + for hw in hardware_items: + adapter = getattr(hw, "adapter", None) + read_odom = getattr(adapter, "read_odom", None) + if read_odom is None: + continue + try: + pose = read_odom() + except Exception as e: + logger.debug(f"read_odom on {type(adapter).__name__} raised: {e}") + continue + if pose is not None: + self._odom_callback(pose) + return + __all__ = ["TickLoop"] diff --git a/dimos/core/global_config.py b/dimos/core/global_config.py index cefd3f1ebc..1555feac8c 100644 --- a/dimos/core/global_config.py +++ b/dimos/core/global_config.py @@ -52,6 +52,7 @@ class GlobalConfig(BaseSettings): nerf_speed: float = 1.0 planner_robot_speed: float | None = None mcp_port: int = 9990 + viser_port: int = 8082 dtop: bool = False obstacle_avoidance: bool = True detection_model: VlModelName = "moondream" diff --git a/dimos/hardware/drive_trains/unitree_g1/__init__.py b/dimos/hardware/drive_trains/unitree_g1/__init__.py new file mode 100644 index 0000000000..34c3e7dba4 --- /dev/null +++ b/dimos/hardware/drive_trains/unitree_g1/__init__.py @@ -0,0 +1,19 @@ +# 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. + +"""Unitree G1 humanoid robot adapter.""" + +from dimos.hardware.drive_trains.unitree_g1.adapter import UnitreeG1TwistAdapter + +__all__ = ["UnitreeG1TwistAdapter"] diff --git a/dimos/hardware/drive_trains/unitree_g1/adapter.py b/dimos/hardware/drive_trains/unitree_g1/adapter.py new file mode 100644 index 0000000000..b5eb272f8a --- /dev/null +++ b/dimos/hardware/drive_trains/unitree_g1/adapter.py @@ -0,0 +1,400 @@ +# 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. + +"""Unitree G1 adapter — wraps Unitree SDK2 LocoClient for humanoid base control. + +The G1 is a humanoid robot with 3 DOF velocity control: [vx, vy, wz]. +This adapter uses the Unitree SDK2 Python bindings to communicate via DDS. + +G1 FSM states (discovered via testing): + FSM 0 = ZeroTorque + FSM 1 = Damp (robot collapses — NEVER call from adapter) + FSM 2 = Squat/Crouch + FSM 3 = Sit + FSM 4 = Lock Stand (rigid standing, no locomotion) + FSM 200 = Start (locomotion active, accepts Move commands) + FSM 702 = Lie2StandUp + FSM 706 = Squat2StandUp + +Initialization sequence: + 1. ChannelFactoryInitialize(0, interface) - Initialize DDS + 2. SetFsmId(4) - Lock stand (FSM 4) + 3. Start() - Activate locomotion (FSM 200) + 4. Move(vx, vy, vyaw) - Send velocity commands + +Shutdown: StopMove() only (robot stays standing). + +Note: Damp() and ZeroTorque() are NEVER called by the adapter — they +cause the robot to collapse and should only be invoked by the user. +""" + +from __future__ import annotations + +from dataclasses import dataclass +import threading +import time +from typing import TYPE_CHECKING + +from dimos.utils.logging_config import setup_logger + +if TYPE_CHECKING: + from unitree_sdk2py.core.channel import ChannelSubscriber # type: ignore[import-untyped] + from unitree_sdk2py.g1.loco.g1_loco_client import LocoClient # type: ignore[import-untyped] + from unitree_sdk2py.idl.unitree_go.msg.dds_ import ( # type: ignore[import-untyped] + SportModeState_, + ) + + from dimos.hardware.drive_trains.registry import TwistBaseAdapterRegistry + +logger = setup_logger() + + +@dataclass +class _Session: + """Active connection state for a G1.""" + + client: LocoClient + lock: threading.Lock + state_sub: ChannelSubscriber | None = None + latest_state: SportModeState_ | None = None + enabled: bool = False + locomotion_ready: bool = False + + +class UnitreeG1TwistAdapter: + """TwistBaseAdapter implementation for Unitree G1 humanoid. + + Communicates with G1 via Unitree SDK2 Python over DDS. + Expects 3 DOF: [vx, vy, wz] where: + - vx: forward/backward velocity (m/s) + - vy: left/right lateral velocity (m/s) + - wz: yaw rotation velocity (rad/s) + + Args: + dof: Number of velocity DOFs (must be 3 for G1) + network_interface: DDS network interface ID or name (default: 0) + """ + + def __init__( + self, + dof: int = 3, + network_interface: int | str | None = None, + address: str | None = None, + **_: object, + ) -> None: + if dof != 3: + raise ValueError(f"G1 only supports 3 DOF (vx, vy, wz), got {dof}") + + # Accept either network_interface= or address= (coordinator passes address=) + self._network_interface = network_interface or address or "eth0" + self._session: _Session | None = None + + def _get_session(self) -> _Session: + """Return active session or raise if not connected.""" + if self._session is None: + raise RuntimeError("G1 not connected") + return self._session + + # ========================================================================= + # Connection + # ========================================================================= + + def connect(self) -> bool: + """Connect to G1 via DDS and initialize the LocoClient.""" + try: + from unitree_sdk2py.core.channel import ChannelFactoryInitialize, ChannelSubscriber + from unitree_sdk2py.g1.loco.g1_loco_client import LocoClient + from unitree_sdk2py.idl.unitree_go.msg.dds_ import SportModeState_ + + # Initialize DDS + logger.info(f"Initializing DDS with network interface {self._network_interface}...") + ChannelFactoryInitialize(0, self._network_interface) + + # Create loco client + logger.info("Connecting to G1 LocoClient...") + client = LocoClient() + client.SetTimeout(10.0) + client.Init() + + # Create session — callback closes over it for state updates + session = _Session(client=client, lock=threading.Lock()) + + def state_callback(msg: SportModeState_) -> None: + with session.lock: + session.latest_state = msg + + state_sub = ChannelSubscriber("rt/sportmodestate", SportModeState_) + state_sub.Init(state_callback, 10) + session.state_sub = state_sub + + self._session = session + logger.info("Connected to G1") + + # Check if robot is freshly booted (FSM 0) — needs manual damp first + fsm = self._get_fsm_id() + if fsm == 0: + logger.warning( + "G1 is in FSM 0 (fresh boot). " + "Please put the robot in DAMP mode manually, then retry. " + "Waiting 10s for damp..." + ) + if not self._wait_for_fsm(1, timeout=30, settle=2): + logger.error("G1 did not enter damp mode (FSM 1). Cannot proceed.") + self.disconnect() + return False + + # Enter lock stand (FSM 4) so the robot is standing and ready + logger.info("Entering lock stand (FSM 4) on G1...") + session.client.SetFsmId(4) + if not self._wait_for_fsm(4): + logger.error("G1 failed to reach lock stand (FSM 4)") + self.disconnect() + return False + + return True + + except Exception as e: + logger.error(f"Failed to connect to G1: {e}") + self._session = None + return False + + def disconnect(self) -> None: + """Disconnect and safely shut down the robot. + + Stops motion but keeps the robot standing (in locomotion mode). + Does NOT call Damp/ZeroTorque/Squat — the user should manage + those transitions manually. + """ + session = self._session + if session is not None: + try: + logger.info("Stopping G1 motion...") + session.client.StopMove() + time.sleep(0.5) + except Exception as e: + logger.error(f"Error during disconnect: {e}") + + if session.state_sub is not None: + try: + session.state_sub.Close() + except Exception as e: + logger.error(f"Error closing state subscriber: {e}") + + self._session = None + + def is_connected(self) -> bool: + """Check if connected to G1.""" + return self._session is not None + + # ========================================================================= + # Info + # ========================================================================= + + def get_dof(self) -> int: + """G1 base is always 3 DOF (vx, vy, wz).""" + return 3 + + # ========================================================================= + # State Reading + # ========================================================================= + + def read_velocities(self) -> list[float]: + """Read actual velocities from SportModeState as [vx, vy, wz].""" + session = self._get_session() + with session.lock: + if session.latest_state is None: + return [0.0, 0.0, 0.0] + try: + state = session.latest_state + return [ + float(state.velocity[0]), # vx + float(state.velocity[1]), # vy + float(state.imu_state.gyroscope[2]), # wz (yaw rate) + ] + except Exception as e: + logger.warning(f"Error reading G1 velocities: {e}") + return [0.0, 0.0, 0.0] + + def read_odometry(self) -> list[float] | None: + """Read odometry from G1 as [x, y, theta]. + + Returns position from SportModeState which provides: + - position[0]: x (meters) + - position[1]: y (meters) + - imu_state.rpy[2]: yaw (radians) + """ + session = self._get_session() + with session.lock: + if session.latest_state is None: + return None + + try: + state = session.latest_state + return [ + float(state.position[0]), + float(state.position[1]), + float(state.imu_state.rpy[2]), # yaw + ] + except Exception as e: + logger.error(f"Error reading G1 odometry: {e}") + return None + + # ========================================================================= + # Control + # ========================================================================= + + def write_velocities(self, velocities: list[float]) -> bool: + """Send velocity command to G1. + + Args: + velocities: [vx, vy, wz] in standard frame (m/s, m/s, rad/s) + """ + if len(velocities) != 3: + return False + + session = self._get_session() + + if not session.enabled: + logger.warning("G1 not enabled, ignoring velocity command") + return False + + if not session.locomotion_ready: + logger.warning("G1 locomotion not ready, ignoring velocity command") + return False + + vx, vy, wz = velocities + return self._send_velocity(vx, vy, wz) + + def write_stop(self) -> bool: + """Stop all motion.""" + session = self._get_session() + try: + session.client.StopMove() + return True + except Exception as e: + logger.error(f"Error stopping G1: {e}") + return False + + # ========================================================================= + # Enable/Disable + # ========================================================================= + + def write_enable(self, enable: bool) -> bool: + """Enable/disable the platform. + + When enabling, ensures the robot is stood up and locomotion is ready. + When disabling, stops motion but keeps standing. + """ + session = self._get_session() + + if enable: + if not session.locomotion_ready: + logger.info("Starting G1 locomotion (FSM 200)...") + session.client.Start() + if not self._wait_for_fsm(200): + logger.error("G1 failed to reach locomotion mode (FSM 200)") + return False + session.locomotion_ready = True + + session.enabled = True + logger.info("G1 enabled") + return True + else: + self.write_stop() + session.enabled = False + logger.info("G1 disabled") + return True + + def read_enabled(self) -> bool: + """Check if platform is enabled.""" + return self._session is not None and self._session.enabled + + # ========================================================================= + # Internal + # ========================================================================= + + def _get_fsm_id(self) -> int | None: + """Query the current FSM ID from the robot. Returns None on failure.""" + import json + + from unitree_sdk2py.g1.loco.g1_loco_api import ( # type: ignore[import-untyped] + ROBOT_API_ID_LOCO_GET_FSM_ID, + ) + + session = self._get_session() + try: + # LocoClient has no public GetFsmId() — _Call is the standard RPC + # dispatch used by all SDK methods (SetFsmId, Move, etc.). + code, data = session.client._Call(ROBOT_API_ID_LOCO_GET_FSM_ID, "{}") + if code == 0 and data: + # data is like '{"data":4}' — parse as JSON for exact match + parsed = json.loads(str(data)) + return int(parsed["data"]) + except Exception as e: + logger.warning(f"Error querying FSM state: {e}") + return None + + def _wait_for_fsm(self, target_fsm: int, timeout: float = 10.0, settle: float = 5.0) -> bool: + """Poll GetFsmId until the robot reports the target FSM state. + + Args: + target_fsm: Expected FSM ID (e.g. 4 for lock stand, 200 for locomotion). + timeout: Maximum seconds to wait before giving up. + settle: Seconds to wait after reaching target state, letting the robot settle. + + Returns: + True if the target state was reached, False on timeout. + """ + deadline = time.time() + timeout + + while time.time() < deadline: + fsm = self._get_fsm_id() + if fsm == target_fsm: + logger.info(f"G1 reached FSM {target_fsm}, settling for {settle}s...") + time.sleep(settle) + return True + time.sleep(1) + + logger.error(f"Timed out waiting for G1 FSM {target_fsm}") + return False + + def _send_velocity(self, vx: float, vy: float, wz: float) -> bool: + """Send raw velocity to G1 via LocoClient.Move(). + + Uses default duration (1 second) since the coordinator tick loop + calls at 100Hz, providing continuous updates. + + Args: + vx: forward/backward velocity (m/s) + vy: left/right lateral velocity (m/s) + wz: yaw rotation velocity (rad/s) + """ + session = self._get_session() + try: + with session.lock: + session.client.Move(vx, vy, wz) + + return True + + except Exception as e: + logger.error(f"Error sending G1 velocity: {e}") + return False + + +def register(registry: TwistBaseAdapterRegistry) -> None: + """Register this adapter with the registry.""" + registry.register("unitree_g1", UnitreeG1TwistAdapter) + + +__all__ = ["UnitreeG1TwistAdapter"] diff --git a/dimos/hardware/drive_trains/unitree_go2/__init__.py b/dimos/hardware/drive_trains/unitree_go2/__init__.py new file mode 100644 index 0000000000..b5b960d874 --- /dev/null +++ b/dimos/hardware/drive_trains/unitree_go2/__init__.py @@ -0,0 +1,19 @@ +# 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. + +"""Unitree Go2 quadruped robot adapter.""" + +from dimos.hardware.drive_trains.unitree_go2.adapter import UnitreeGo2Adapter + +__all__ = ["UnitreeGo2Adapter"] diff --git a/dimos/hardware/whole_body/__init__.py b/dimos/hardware/whole_body/__init__.py new file mode 100644 index 0000000000..8e8e0ccabd --- /dev/null +++ b/dimos/hardware/whole_body/__init__.py @@ -0,0 +1,15 @@ +# 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. + +"""Quadruped hardware adapters for joint-level control.""" diff --git a/dimos/hardware/whole_body/mujoco/__init__.py b/dimos/hardware/whole_body/mujoco/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/dimos/hardware/whole_body/mujoco/g1/__init__.py b/dimos/hardware/whole_body/mujoco/g1/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/dimos/hardware/whole_body/mujoco/g1/adapter.py b/dimos/hardware/whole_body/mujoco/g1/adapter.py new file mode 100644 index 0000000000..81dad333ba --- /dev/null +++ b/dimos/hardware/whole_body/mujoco/g1/adapter.py @@ -0,0 +1,220 @@ +# 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 simulation ``WholeBodyAdapter`` for the Unitree G1. + +Pairs with ``MujocoSimModule`` (in-process MuJoCo engine + SHM publisher). +The blueprint composes both modules; they share the same ``MujocoEngine`` +indirectly via SHM keyed on the MJCF path. + +The adapter conforms to the same ``WholeBodyAdapter`` Protocol the real-hw +DDS adapter implements, so ControlCoordinator (and the GR00T WBC task on +top of it) can't tell sim from real. +""" + +from __future__ import annotations + +import math +import time +from typing import TYPE_CHECKING, Any + +from dimos.hardware.whole_body.spec import ( + POS_STOP, + IMUState, + MotorCommand, + MotorState, +) +from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped +from dimos.simulation.engines.mujoco_shm import ( + ManipShmReader, + shm_key_from_path, +) +from dimos.utils.logging_config import setup_logger + +if TYPE_CHECKING: + from dimos.hardware.whole_body.registry import WholeBodyAdapterRegistry + +logger = setup_logger() + +_NUM_MOTORS = 29 + +_READY_WAIT_TIMEOUT_S = 60.0 +_READY_WAIT_POLL_S = 0.1 +_ATTACH_RETRY_TIMEOUT_S = 30.0 +_ATTACH_RETRY_POLL_S = 0.2 + + +class SimMujocoG1WholeBodyAdapter: + """G1 ``WholeBodyAdapter`` that proxies to a ``MujocoSimModule`` via SHM. + + The sim module owns the engine and publishes joint state + IMU into + SHM each step; this adapter reads them and forwards per-joint + (q, kp, kd, tau) commands back into SHM for the engine's pre-step + PD-with-feedforward hook to apply. + + ``address`` (the MJCF XML path) is the discovery key — both sides + derive the same SHM names from it via ``shm_key_from_path``. + """ + + def __init__( + self, + network_interface: int | str = 0, + domain_id: int = 0, + address: str | None = None, + **_: Any, + ) -> None: + if address is None: + raise ValueError( + "SimMujocoG1WholeBodyAdapter: address (MJCF XML path) is required — " + "set HardwareComponent.address to the same MJCF path the " + "MujocoSimModule loads." + ) + self._address = address + self._shm_key = shm_key_from_path(address) + self._shm: ManipShmReader | None = None + self._connected = False + + # ------------------------------------------------------------------ + # Lifecycle + # ------------------------------------------------------------------ + + def connect(self) -> bool: + # Attach with retry — MujocoSimModule may still be starting up. + deadline = time.monotonic() + _ATTACH_RETRY_TIMEOUT_S + while True: + try: + self._shm = ManipShmReader(self._shm_key) + break + except FileNotFoundError: + if time.monotonic() > deadline: + logger.error( + "SimMujocoG1WholeBodyAdapter: SHM buffers not found", + address=self._address, + shm_key=self._shm_key, + timeout_s=_ATTACH_RETRY_TIMEOUT_S, + ) + return False + time.sleep(_ATTACH_RETRY_POLL_S) + + # Wait for the sim to signal ready (engine connected, first + # joint-state packet written). Without this the first + # read_motor_states() returns zeros and the WBC obs is junk. + deadline = time.monotonic() + _READY_WAIT_TIMEOUT_S + while not self._shm.is_ready(): + if time.monotonic() > deadline: + logger.error( + "SimMujocoG1WholeBodyAdapter: sim module not ready", + timeout_s=_READY_WAIT_TIMEOUT_S, + ) + self._shm.cleanup() + self._shm = None + return False + time.sleep(_READY_WAIT_POLL_S) + + self._connected = True + logger.info( + "SimMujocoG1WholeBodyAdapter connected", + num_motors=_NUM_MOTORS, + shm_key=self._shm_key, + ) + return True + + def disconnect(self) -> None: + if self._shm is not None: + try: + self._shm.cleanup() + except Exception as e: # best-effort cleanup + logger.warning(f"SHM cleanup raised: {e}") + self._shm = None + self._connected = False + + def is_connected(self) -> bool: + return self._connected and self._shm is not None + + # ------------------------------------------------------------------ + # IO (WholeBodyAdapter protocol) + # ------------------------------------------------------------------ + + def read_motor_states(self) -> list[MotorState]: + if not self._connected or self._shm is None: + return [MotorState()] * _NUM_MOTORS + positions = self._shm.read_positions(_NUM_MOTORS) + velocities = self._shm.read_velocities(_NUM_MOTORS) + efforts = self._shm.read_efforts(_NUM_MOTORS) + return [ + MotorState(q=positions[i], dq=velocities[i], tau=efforts[i]) for i in range(_NUM_MOTORS) + ] + + def has_motor_states(self) -> bool: + # Sim ground truth is available the moment SHM attaches. + # No ramp-up window like real DDS adapters need before the + # first state msg arrives. + return self._connected and self._shm is not None + + def read_imu(self) -> IMUState: + if not self._connected or self._shm is None: + return IMUState() + quat, gyro, accel = self._shm.read_imu() + # Derive ZYX Euler from the quaternion — matches the real G1 adapter. + w, x, y, z = quat + sinr = 2.0 * (w * x + y * z) + cosr = 1.0 - 2.0 * (x * x + y * y) + roll = math.atan2(sinr, cosr) + sinp = 2.0 * (w * y - z * x) + pitch = math.copysign(math.pi / 2.0, sinp) if abs(sinp) >= 1.0 else math.asin(sinp) + siny = 2.0 * (w * z + x * y) + cosy = 1.0 - 2.0 * (y * y + z * z) + yaw = math.atan2(siny, cosy) + return IMUState( + quaternion=quat, + gyroscope=gyro, + accelerometer=accel, + rpy=(roll, pitch, yaw), + ) + + def read_odom(self) -> PoseStamped | None: + # MujocoSimModule publishes the floating-base pose on its own + # ``odom`` Out port (TBD); the adapter doesn't currently route + # odom through SHM. Returning None matches the real-hw G1 + # adapter behaviour (no onboard estimator → no odom). + return None + + def write_motor_commands(self, commands: list[MotorCommand]) -> bool: + if not self._connected or self._shm is None: + return False + if len(commands) != _NUM_MOTORS: + logger.error( + f"SimMujocoG1WholeBodyAdapter: expected {_NUM_MOTORS} commands, got {len(commands)}" + ) + return False + # Flatten the per-motor command into per-joint arrays. POS_STOP + # ("no command") is replaced with 0.0 — the engine's PD only + # acts when kp > 0 anyway, so a zeroed q is harmless. + q = [cmd.q if cmd.q != POS_STOP else 0.0 for cmd in commands] + kp = [cmd.kp for cmd in commands] + kd = [cmd.kd for cmd in commands] + tau = [cmd.tau for cmd in commands] + self._shm.write_position_command(q) + self._shm.write_kp_command(kp) + self._shm.write_kd_command(kd) + self._shm.write_tau_command(tau) + return True + + +def register(registry: WholeBodyAdapterRegistry) -> None: + """Register with the whole-body adapter registry.""" + registry.register("sim_mujoco_g1", SimMujocoG1WholeBodyAdapter) + + +__all__ = ["SimMujocoG1WholeBodyAdapter"] diff --git a/dimos/hardware/whole_body/registry.py b/dimos/hardware/whole_body/registry.py index ddab15b0fc..993069f1c3 100644 --- a/dimos/hardware/whole_body/registry.py +++ b/dimos/hardware/whole_body/registry.py @@ -17,11 +17,19 @@ Mirrors the TwistBaseAdapterRegistry pattern: each subpackage provides a ``register(registry)`` function in its ``adapter.py`` module. +Discovery handles two layouts so both flat ("kind") and nested +("vendor/robot") subpackages register correctly: + +* ``dimos/hardware/whole_body//adapter.py`` — Mustafa's transport + adapter (``transport/adapter.py``). +* ``dimos/hardware/whole_body///adapter.py`` — our + MuJoCo sim adapter (``mujoco/g1/adapter.py``). + Usage: from dimos.hardware.whole_body.registry import whole_body_adapter_registry - adapter = whole_body_adapter_registry.create("unitree_go2") - print(whole_body_adapter_registry.available()) # ["unitree_go2"] + adapter = whole_body_adapter_registry.create("sim_mujoco_g1") + print(whole_body_adapter_registry.available()) # ["sim_mujoco_g1", ...] """ from __future__ import annotations @@ -64,20 +72,35 @@ def available(self) -> list[str]: return sorted(self._adapters.keys()) def discover(self) -> None: - """Discover and register adapters from subpackages.""" + """Discover and register adapters from subpackages. + + Walks ``dimos/hardware/whole_body/`` recursively (max depth 2) + looking for ``adapter.py`` modules with a ``register(registry)`` + function. Skips dunder/dot directories. + """ import dimos.hardware.whole_body as pkg pkg_dir = pkg.__path__[0] - for entry in sorted(os.listdir(pkg_dir)): - entry_path = os.path.join(pkg_dir, entry) + self._discover_in("dimos.hardware.whole_body", pkg_dir, max_depth=2) + + def _discover_in(self, pkg_path: str, dir_path: str, *, max_depth: int) -> None: + for entry in sorted(os.listdir(dir_path)): + entry_path = os.path.join(dir_path, entry) if not os.path.isdir(entry_path) or entry.startswith(("_", ".")): continue + sub_pkg_path = f"{pkg_path}.{entry}" + adapter_module = f"{sub_pkg_path}.adapter" try: - mod = importlib.import_module(f"dimos.hardware.whole_body.{entry}.adapter") - if hasattr(mod, "register"): - mod.register(self) + mod = importlib.import_module(adapter_module) except ImportError as e: - logger.warning(f"Skipping whole-body adapter {entry}: {e}") + # No adapter.py at this level — recurse one deeper if budget left. + if max_depth > 1: + self._discover_in(sub_pkg_path, entry_path, max_depth=max_depth - 1) + else: + logger.warning(f"Skipping whole-body adapter {entry}: {e}") + continue + if hasattr(mod, "register"): + mod.register(self) whole_body_adapter_registry = WholeBodyAdapterRegistry() diff --git a/dimos/hardware/whole_body/spec.py b/dimos/hardware/whole_body/spec.py index 4645e8c44e..3535f35ff0 100644 --- a/dimos/hardware/whole_body/spec.py +++ b/dimos/hardware/whole_body/spec.py @@ -12,14 +12,24 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""WholeBodyAdapter protocol for joint-level (q/dq/kp/kd/tau) motor control.""" +"""WholeBodyAdapter protocol for joint-level motor control. + +Lightweight protocol for robots that expose per-motor +position/velocity/torque control (as opposed to TwistBaseAdapter which +only exposes velocity commands). + +Supports any number of motors — quadrupeds (12 DOF), humanoids (29 DOF), etc. +""" from __future__ import annotations from dataclasses import dataclass -from typing import Protocol, runtime_checkable +from typing import TYPE_CHECKING, Protocol, runtime_checkable + +if TYPE_CHECKING: + from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped -# Unitree SDK sentinels meaning "no command" for that DOF. +# Sentinel values from Unitree SDK — used to signal "no command" for a DOF. POS_STOP: float = 2.146e9 VEL_STOP: float = 16000.0 @@ -54,17 +64,88 @@ class IMUState: rpy: tuple[float, float, float] = (0.0, 0.0, 0.0) +@dataclass(frozen=True) +class WholeBodyConfig: + """Whole-body-specific component config. + + Lives on ``HardwareComponent.wb_config`` for components of type WHOLE_BODY. + Keeps PD gains (and any future whole-body-only knobs) off the generic + HardwareComponent shared by all hardware kinds. + + Attributes: + kp: Per-joint position gains used by ConnectedWholeBody when + translating position commands to MotorCommand. Length must + match the component's ``joints`` list when set. + kd: Per-joint velocity gains. Same length constraint. + """ + + kp: tuple[float, ...] | None = None + kd: tuple[float, ...] | None = None + + @runtime_checkable class WholeBodyAdapter(Protocol): - """Joint-level whole-body motor IO. SI units (rad, rad/s, Nm).""" + """Protocol for joint-level whole-body motor IO. + + Implement this per vendor SDK. All methods use SI units: + - Position: radians + - Velocity: rad/s + - Torque: Nm + - Force: N + """ + + # --- Connection --- + + def connect(self) -> bool: + """Connect to hardware. Returns True on success.""" + ... + + def disconnect(self) -> None: + """Disconnect from hardware.""" + ... + + def is_connected(self) -> bool: + """Check if connected.""" + ... + + # --- State Reading --- + + def read_motor_states(self) -> list[MotorState]: + """Read motor states for all joints.""" + ... + + def has_motor_states(self) -> bool: + """Whether ``read_motor_states`` will return live data. + + Real-hardware adapters return False until the first DDS state + message arrives; sim adapters that always have ground truth + can hardcode True. ConnectedWholeBody uses this to defer + publishing joint_state until the adapter is producing real + feedback, avoiding a leading zero-quat pose. + """ + ... + + def read_imu(self) -> IMUState: + """Read IMU state.""" + ... + + def read_odom(self) -> PoseStamped | None: + """Read latest base pose in world frame, if the adapter has one. + + Sim adapters return the simulator's ground-truth base pose. + Real-hardware adapters return None unless they wire up an + onboard estimator (IMU + leg kinematics fusion, DDS odom topic, + ROS /odom subscription, etc.). The coordinator publishes + ``odom: Out[PoseStamped]`` only when this returns a value, so a + ``None`` return is a quiet no-op rather than a default zero pose. + """ + return None + + # --- Control --- - def connect(self) -> bool: ... - def disconnect(self) -> None: ... - def is_connected(self) -> bool: ... - def read_motor_states(self) -> list[MotorState]: ... - def has_motor_states(self) -> bool: ... - def read_imu(self) -> IMUState: ... - def write_motor_commands(self, commands: list[MotorCommand]) -> bool: ... + def write_motor_commands(self, commands: list[MotorCommand]) -> bool: + """Write motor commands for all joints. Returns success.""" + ... __all__ = [ @@ -74,4 +155,5 @@ def write_motor_commands(self, commands: list[MotorCommand]) -> bool: ... "MotorCommand", "MotorState", "WholeBodyAdapter", + "WholeBodyConfig", ] diff --git a/dimos/hardware/whole_body/unitree/__init__.py b/dimos/hardware/whole_body/unitree/__init__.py new file mode 100644 index 0000000000..5bfe622b00 --- /dev/null +++ b/dimos/hardware/whole_body/unitree/__init__.py @@ -0,0 +1,15 @@ +# 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. + +"""Unitree quadruped adapters.""" diff --git a/dimos/hardware/whole_body/unitree/g1/__init__.py b/dimos/hardware/whole_body/unitree/g1/__init__.py new file mode 100644 index 0000000000..e69de29bb2 diff --git a/dimos/hardware/whole_body/unitree/g1/adapter.py b/dimos/hardware/whole_body/unitree/g1/adapter.py new file mode 100644 index 0000000000..29462d1536 --- /dev/null +++ b/dimos/hardware/whole_body/unitree/g1/adapter.py @@ -0,0 +1,302 @@ +# 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. + +"""Unitree G1 low-level adapter -- direct 29-DOF joint control over DDS. + +Uses ``rt/lowcmd`` / ``rt/lowstate`` DDS topics for motor-level +position/velocity/torque control, bypassing the high-level LocoClient. + +Important: The G1 must first exit sport mode (via MotionSwitcherClient) +before low-level commands are accepted. + +Motor ordering (29 joints): + 0-5: Left leg (HipPitch, HipRoll, HipYaw, Knee, AnklePitch, AnkleRoll) + 6-11: Right leg + 12: WaistYaw + 13-14: WaistRoll, WaistPitch (may be invalid on some variants) + 15-21: Left arm (ShoulderPitch, ShoulderRoll, ShoulderYaw, Elbow, + WristRoll, WristPitch, WristYaw) + 22-28: Right arm + +G1-specific protocol details: + - Uses ``unitree_hg`` IDL types (not ``unitree_go`` like the Go2) + - LowCmd has ``mode_pr`` and ``mode_machine`` fields instead of head/level_flag + - ``mode_machine`` must be read from LowState and echoed back in every LowCmd + - Motor array has 35 slots (only 29 are used) +""" + +from __future__ import annotations + +import threading +import time +from typing import TYPE_CHECKING + +from dimos.hardware.whole_body.spec import ( + POS_STOP, + VEL_STOP, + IMUState, + MotorCommand, + MotorState, +) +from dimos.utils.logging_config import setup_logger + +if TYPE_CHECKING: + from dimos.hardware.whole_body.registry import WholeBodyAdapterRegistry + from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped + +logger = setup_logger() + +_NUM_MOTORS = 29 +_NUM_MOTOR_SLOTS = 35 + + +class UnitreeG1LowLevelAdapter: + """WholeBodyAdapter implementation for Unitree G1 -- low-level DDS. + + The coordinator's tick loop drives the publish cadence. Each call to + ``write_motor_commands()`` updates the ``LowCmd_`` buffer, computes + CRC, and publishes immediately -- no background thread needed. + + Args: + network_interface: DDS network interface name or ID (default: "eth0"). + domain_id: DDS domain ID. Real robot uses 0; unitree_mujoco sim + defaults to 1. Changing domain lets the same adapter bind to + sim or real with no code change. + """ + + def __init__( + self, + network_interface: int | str = 0, + domain_id: int = 0, + **_: object, + ) -> None: + self._network_interface = network_interface + self._domain_id = domain_id + + self._connected = False + self._lock = threading.Lock() + + # SDK objects (lazy-imported on connect) + self._low_cmd = None + self._publisher = None + self._subscriber = None + self._crc = None + + # Latest feedback + self._low_state = None + + # mode_machine must be read from first LowState and echoed back + self._mode_machine: int | None = None + + # ========================================================================= + # Connection + # ========================================================================= + + def connect(self) -> bool: + """Connect to G1 and release sport mode for low-level control.""" + try: + from unitree_sdk2py.core.channel import ( + ChannelFactoryInitialize, + ChannelPublisher, + ChannelSubscriber, + ) + from unitree_sdk2py.idl.default import unitree_hg_msg_dds__LowCmd_ + from unitree_sdk2py.idl.unitree_hg.msg.dds_ import LowCmd_, LowState_ + from unitree_sdk2py.utils.crc import CRC + + # 1. Initialise DDS transport. NOTE: the cyclonedds Python + # wheel reads CYCLONEDDS_HOME at runtime — it must point at + # the local cyclonedds install (e.g. ~/cyclonedds/install) + # before this call or DDS topic creation later fails with + # PRECONDITION_NOT_MET. Add to your shell rc. + logger.info( + f"Initializing DDS (G1 low-level) with interface {self._network_interface} " + f"on domain {self._domain_id}..." + ) + ChannelFactoryInitialize(self._domain_id, self._network_interface) + + # 2. Create publisher / subscriber + self._publisher = ChannelPublisher("rt/lowcmd", LowCmd_) + self._publisher.Init() + + self._subscriber = ChannelSubscriber("rt/lowstate", LowState_) + self._subscriber.Init(self._on_low_state, 10) + + # 3. Initialise LowCmd with safe defaults + self._low_cmd = unitree_hg_msg_dds__LowCmd_() + self._low_cmd.mode_pr = 0 # PR mode (Pitch/Roll) + for i in range(_NUM_MOTOR_SLOTS): + self._low_cmd.motor_cmd[i].mode = 0x01 # Enable + self._low_cmd.motor_cmd[i].q = POS_STOP + self._low_cmd.motor_cmd[i].kp = 0 + self._low_cmd.motor_cmd[i].dq = VEL_STOP + self._low_cmd.motor_cmd[i].kd = 0 + self._low_cmd.motor_cmd[i].tau = 0 + + self._crc = CRC() + + # 4. Release sport mode so low-level commands are accepted + logger.info("Releasing sport mode...") + self._release_sport_mode() + + # 5. Wait for first LowState to get mode_machine + logger.info("Waiting for first LowState to capture mode_machine...") + deadline = time.time() + 10.0 + while self._mode_machine is None and time.time() < deadline: + time.sleep(0.1) + + if self._mode_machine is None: + logger.error("Timed out waiting for LowState — mode_machine not captured") + self._connected = False + return False + + self._connected = True + logger.info(f"G1 low-level adapter connected (mode_machine={self._mode_machine})") + return True + + except Exception: + logger.exception("Failed to connect G1 low-level adapter (full traceback):") + self._connected = False + return False + + def disconnect(self) -> None: + """Disconnect from the robot.""" + self._connected = False + self._publisher = None + self._subscriber = None + self._low_cmd = None + self._low_state = None + self._mode_machine = None + logger.info("G1 low-level adapter disconnected") + + def is_connected(self) -> bool: + return self._connected + + # ========================================================================= + # State Reading + # ========================================================================= + + def read_motor_states(self) -> list[MotorState]: + """Read motor states for all 29 joints.""" + with self._lock: + if self._low_state is None: + return [MotorState()] * _NUM_MOTORS + return [ + MotorState( + q=self._low_state.motor_state[i].q, + dq=self._low_state.motor_state[i].dq, + tau=self._low_state.motor_state[i].tau_est, + ) + for i in range(_NUM_MOTORS) + ] + + def read_imu(self) -> IMUState: + """Read IMU state.""" + with self._lock: + if self._low_state is None: + return IMUState() + imu = self._low_state.imu_state + return IMUState( + quaternion=tuple(imu.quaternion), + gyroscope=tuple(imu.gyroscope), + accelerometer=tuple(imu.accelerometer), + rpy=tuple(imu.rpy), + ) + + def read_odom(self) -> PoseStamped | None: + """Real G1 odom — not yet wired. + + The unitree_sdk2py LowState only carries IMU + motor data, not a + base-frame pose; the production pipeline computes odometry by + fusing IMU integration with leg kinematics in a separate node. + Returning None keeps the coordinator's Out[odom] silent on real + hardware. Wire this up by either (a) subscribing to the DDS + odometry topic published by the onboard estimator if available, + or (b) running a small estimator inside this adapter. + """ + return None + + # ========================================================================= + # Control + # ========================================================================= + + def write_motor_commands(self, commands: list[MotorCommand]) -> bool: + """Update command buffer, compute CRC, and publish immediately. + + Called by the coordinator tick loop on every tick -- no background + thread needed. + """ + if len(commands) != _NUM_MOTORS: + logger.error(f"Expected {_NUM_MOTORS} commands, got {len(commands)}") + return False + + with self._lock: + if self._low_cmd is None or self._crc is None or self._publisher is None: + return False + if self._mode_machine is None: + return False + + # Echo mode_machine from latest LowState + self._low_cmd.mode_machine = self._mode_machine + + for i, cmd in enumerate(commands): + self._low_cmd.motor_cmd[i].q = cmd.q + self._low_cmd.motor_cmd[i].dq = cmd.dq + self._low_cmd.motor_cmd[i].kp = cmd.kp + self._low_cmd.motor_cmd[i].kd = cmd.kd + self._low_cmd.motor_cmd[i].tau = cmd.tau + self._low_cmd.crc = self._crc.Crc(self._low_cmd) + self._publisher.Write(self._low_cmd) + return True + + # ========================================================================= + # Internal + # ========================================================================= + + def _on_low_state(self, msg: object) -> None: + """DDS callback for rt/lowstate.""" + with self._lock: + self._low_state = msg + # Capture mode_machine from first LowState + if self._mode_machine is None: + self._mode_machine = msg.mode_machine # type: ignore[attr-defined] + + def _release_sport_mode(self) -> None: + """Exit sport mode so that low-level commands are accepted. + + Loops ReleaseMode until CheckMode returns empty. + """ + from unitree_sdk2py.comm.motion_switcher.motion_switcher_client import ( + MotionSwitcherClient, + ) + + msc = MotionSwitcherClient() + msc.SetTimeout(5.0) + msc.Init() + + _status, result = msc.CheckMode() + while result["name"]: + msc.ReleaseMode() + _status, result = msc.CheckMode() + time.sleep(1) + + logger.info("Sport mode released -- low-level control active") + + +def register(registry: WholeBodyAdapterRegistry) -> None: + """Register this adapter with the whole-body registry.""" + registry.register("unitree_g1", UnitreeG1LowLevelAdapter) + + +__all__ = ["UnitreeG1LowLevelAdapter"] diff --git a/dimos/hardware/whole_body/unitree/go2/__init__.py b/dimos/hardware/whole_body/unitree/go2/__init__.py new file mode 100644 index 0000000000..1582089168 --- /dev/null +++ b/dimos/hardware/whole_body/unitree/go2/__init__.py @@ -0,0 +1,15 @@ +# 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. + +"""Unitree Go2 low-level quadruped adapter.""" diff --git a/dimos/hardware/whole_body/unitree/go2/adapter.py b/dimos/hardware/whole_body/unitree/go2/adapter.py new file mode 100644 index 0000000000..6e6415964c --- /dev/null +++ b/dimos/hardware/whole_body/unitree/go2/adapter.py @@ -0,0 +1,254 @@ +# 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. + +"""Unitree Go2 low-level adapter — direct 12-DOF joint control over DDS. + +Uses ``rt/lowcmd`` / ``rt/lowstate`` DDS topics for 500 Hz motor-level +position/velocity/torque control, bypassing the high-level SportClient. + +Important: The Go2 must first exit sport mode (via MotionSwitcherClient) +before low-level commands are accepted. + +Motor ordering (12 leg joints): + 0-2: FR (hip, thigh, calf) + 3-5: FL + 6-8: RR + 9-11: RL +""" + +from __future__ import annotations + +import threading +import time +from typing import TYPE_CHECKING + +from dimos.hardware.whole_body.spec import ( + POS_STOP, + VEL_STOP, + IMUState, + MotorCommand, + MotorState, +) +from dimos.utils.logging_config import setup_logger + +if TYPE_CHECKING: + from dimos.hardware.whole_body.registry import WholeBodyAdapterRegistry + +logger = setup_logger() + +_NUM_MOTORS = 12 + + +class UnitreeGo2LowLevelAdapter: + """WholeBodyAdapter implementation for Unitree Go2 — low-level DDS. + + The coordinator's tick loop drives the publish cadence. Each call to + ``write_motor_commands()`` updates the ``LowCmd_`` buffer, computes + CRC, and publishes immediately — no background thread needed. + + Args: + network_interface: DDS network interface ID (default: 0). + """ + + def __init__(self, network_interface: int = 0, **_: object) -> None: + self._network_interface = network_interface + + self._connected = False + self._lock = threading.Lock() + + # SDK objects (lazy-imported on connect) + self._low_cmd = None + self._publisher = None + self._subscriber = None + self._crc = None + + # Latest feedback + self._low_state = None + + # ========================================================================= + # Connection + # ========================================================================= + + def connect(self) -> bool: + """Connect to Go2 and release sport mode for low-level control.""" + try: + from unitree_sdk2py.core.channel import ( + ChannelFactoryInitialize, + ChannelPublisher, + ChannelSubscriber, + ) + from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowCmd_ + from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowCmd_, LowState_ + from unitree_sdk2py.utils.crc import CRC + + # 1. Initialise DDS transport + logger.info(f"Initializing DDS (low-level) with interface {self._network_interface}...") + ChannelFactoryInitialize(self._network_interface) + + # 2. Create publisher / subscriber + self._publisher = ChannelPublisher("rt/lowcmd", LowCmd_) + self._publisher.Init() + + self._subscriber = ChannelSubscriber("rt/lowstate", LowState_) + self._subscriber.Init(self._on_low_state, 10) + + # 3. Initialise LowCmd with safe defaults + self._low_cmd = unitree_go_msg_dds__LowCmd_() + self._low_cmd.head[0] = 0xFE + self._low_cmd.head[1] = 0xEF + self._low_cmd.level_flag = 0xFF + self._low_cmd.gpio = 0 + for i in range(20): + self._low_cmd.motor_cmd[i].mode = 0x01 # PMSM mode + self._low_cmd.motor_cmd[i].q = POS_STOP + self._low_cmd.motor_cmd[i].kp = 0 + self._low_cmd.motor_cmd[i].dq = VEL_STOP + self._low_cmd.motor_cmd[i].kd = 0 + self._low_cmd.motor_cmd[i].tau = 0 + + self._crc = CRC() + + # 4. Release sport mode so low-level commands are accepted + logger.info("Releasing sport mode...") + self._release_sport_mode() + + self._connected = True + logger.info("Go2 low-level adapter connected") + return True + + except Exception as e: + logger.error(f"Failed to connect Go2 low-level adapter: {e}") + self._connected = False + return False + + def disconnect(self) -> None: + """Disconnect from the robot.""" + self._connected = False + self._publisher = None + self._subscriber = None + self._low_cmd = None + self._low_state = None + logger.info("Go2 low-level adapter disconnected") + + def is_connected(self) -> bool: + return self._connected + + # ========================================================================= + # State Reading + # ========================================================================= + + def read_motor_states(self) -> list[MotorState]: + """Read motor states for all 12 leg joints.""" + with self._lock: + if self._low_state is None: + return [MotorState()] * _NUM_MOTORS + return [ + MotorState( + q=self._low_state.motor_state[i].q, + dq=self._low_state.motor_state[i].dq, + tau=self._low_state.motor_state[i].tau_est, + ) + for i in range(_NUM_MOTORS) + ] + + def read_imu(self) -> IMUState: + """Read IMU state.""" + with self._lock: + if self._low_state is None: + return IMUState() + imu = self._low_state.imu_state + return IMUState( + quaternion=tuple(imu.quaternion), + gyroscope=tuple(imu.gyroscope), + accelerometer=tuple(imu.accelerometer), + rpy=tuple(imu.rpy), + ) + + def read_foot_forces(self) -> list[float]: + """Read foot force sensors (4 feet).""" + with self._lock: + if self._low_state is None: + return [0.0] * 4 + return [float(self._low_state.foot_force[i]) for i in range(4)] + + # ========================================================================= + # Control + # ========================================================================= + + def write_motor_commands(self, commands: list[MotorCommand]) -> bool: + """Update command buffer, compute CRC, and publish immediately. + + Called by the coordinator tick loop on every tick — no background + thread needed. + """ + if len(commands) != _NUM_MOTORS: + logger.error(f"Expected {_NUM_MOTORS} commands, got {len(commands)}") + return False + + with self._lock: + if self._low_cmd is None or self._crc is None or self._publisher is None: + return False + for i, cmd in enumerate(commands): + self._low_cmd.motor_cmd[i].q = cmd.q + self._low_cmd.motor_cmd[i].dq = cmd.dq + self._low_cmd.motor_cmd[i].kp = cmd.kp + self._low_cmd.motor_cmd[i].kd = cmd.kd + self._low_cmd.motor_cmd[i].tau = cmd.tau + self._low_cmd.crc = self._crc.Crc(self._low_cmd) + self._publisher.Write(self._low_cmd) + return True + + # ========================================================================= + # Internal + # ========================================================================= + + def _on_low_state(self, msg: object) -> None: + """DDS callback for rt/lowstate.""" + with self._lock: + self._low_state = msg + + def _release_sport_mode(self) -> None: + """Exit sport mode so that low-level commands are accepted. + + Loops StandDown + ReleaseMode until CheckMode returns empty. + """ + from unitree_sdk2py.comm.motion_switcher.motion_switcher_client import ( + MotionSwitcherClient, + ) + from unitree_sdk2py.go2.sport.sport_client import SportClient + + sc = SportClient() + sc.SetTimeout(5.0) + sc.Init() + + msc = MotionSwitcherClient() + msc.SetTimeout(5.0) + msc.Init() + + _status, result = msc.CheckMode() + while result["name"]: + sc.StandDown() + msc.ReleaseMode() + _status, result = msc.CheckMode() + time.sleep(1) + + logger.info("Sport mode released — low-level control active") + + +def register(registry: WholeBodyAdapterRegistry) -> None: + """Register this adapter with the whole-body registry.""" + registry.register("unitree_go2", UnitreeGo2LowLevelAdapter) + + +__all__ = ["UnitreeGo2LowLevelAdapter"] diff --git a/dimos/robot/all_blueprints.py b/dimos/robot/all_blueprints.py index 8d544dff70..e71516741f 100644 --- a/dimos/robot/all_blueprints.py +++ b/dimos/robot/all_blueprints.py @@ -79,6 +79,8 @@ "unitree-g1-coordinator": "dimos.robot.unitree.g1.blueprints.basic.unitree_g1_coordinator:unitree_g1_coordinator", "unitree-g1-detection": "dimos.robot.unitree.g1.blueprints.perceptive.unitree_g1_detection:unitree_g1_detection", "unitree-g1-full": "dimos.robot.unitree.g1.blueprints.agentic.unitree_g1_full:unitree_g1_full", + "unitree-g1-groot-wbc": "dimos.robot.unitree.g1.blueprints.basic.unitree_g1_groot_wbc:unitree_g1_groot_wbc", + "unitree-g1-groot-wbc-sim": "dimos.robot.unitree.g1.blueprints.basic.unitree_g1_groot_wbc_sim:unitree_g1_groot_wbc_sim", "unitree-g1-joystick": "dimos.robot.unitree.g1.blueprints.basic.unitree_g1_joystick:unitree_g1_joystick", "unitree-g1-shm": "dimos.robot.unitree.g1.blueprints.perceptive.unitree_g1_shm:unitree_g1_shm", "unitree-g1-sim": "dimos.robot.unitree.g1.blueprints.perceptive.unitree_g1_sim:unitree_g1_sim", diff --git a/dimos/robot/unitree/g1/blueprints/basic/_groot_wbc_common.py b/dimos/robot/unitree/g1/blueprints/basic/_groot_wbc_common.py new file mode 100644 index 0000000000..f0fb9da6ed --- /dev/null +++ b/dimos/robot/unitree/g1/blueprints/basic/_groot_wbc_common.py @@ -0,0 +1,116 @@ +# 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. + +"""Shared GR00T WBC config — joint lists, gain tables, default arm pose. + +Imported by both ``unitree_g1_groot_wbc`` (real hardware) and +``unitree_g1_groot_wbc_sim`` (MuJoCo + viser + splat camera). The two +blueprints differ only in module composition (which adapter, whether +the viser viewer + splat camera modules are wired) and in the arming +defaults that match each mode's safety needs; everything that's +genuinely identical (gain tables, joint ordering, the trained-pose +zero offset) lives here. +""" + +from __future__ import annotations + +from dimos.control.components import make_humanoid_joints + +g1_joints = make_humanoid_joints("g1") +g1_legs_waist = g1_joints[:15] # indices 0..14 — legs (12) + waist (3) +g1_arms = g1_joints[15:] # indices 15..28 — left arm (7) + right arm (7) + +# Per-joint PD gains, 29 entries in DDS motor order. Lifted verbatim +# from g1-control-api/configs/g1_groot_wbc.yaml, which itself copies +# GR00T-WBC's g1_29dof_gear_wbc.yaml reference config. These gains +# are the ones the balance / walk ONNX policies were trained against — +# diverging from them on real hardware risks instability. +G1_GROOT_KP: list[float] = [ + 150.0, + 150.0, + 150.0, + 200.0, + 40.0, + 40.0, # left leg + 150.0, + 150.0, + 150.0, + 200.0, + 40.0, + 40.0, # right leg + 250.0, + 250.0, + 250.0, # waist + 100.0, + 100.0, + 40.0, + 40.0, + 20.0, + 20.0, + 20.0, # left arm + 100.0, + 100.0, + 40.0, + 40.0, + 20.0, + 20.0, + 20.0, # right arm +] +G1_GROOT_KD: list[float] = [ + 2.0, + 2.0, + 2.0, + 4.0, + 2.0, + 2.0, # left leg + 2.0, + 2.0, + 2.0, + 4.0, + 2.0, + 2.0, # right leg + 5.0, + 5.0, + 5.0, # waist + 5.0, + 5.0, + 2.0, + 2.0, + 2.0, + 2.0, + 2.0, # left arm + 5.0, + 5.0, + 2.0, + 2.0, + 2.0, + 2.0, + 2.0, # right arm +] + +# Relaxed arms-down pose. Values taken from +# g1_control/backends/groot_wbc_backend.py:DEFAULT_29[15:] (all zeros), +# the zero-offset pose the policy was trained against. Operators can +# override at runtime by publishing joint targets on the arms via the +# coordinator's ``joint_command`` transport. +ARM_DEFAULT_POSE: list[float] = [0.0] * 14 + +__all__ = [ + "ARM_DEFAULT_POSE", + "G1_GROOT_KD", + "G1_GROOT_KP", + "g1_arms", + "g1_joints", + "g1_legs_waist", +] diff --git a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc.py b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc.py new file mode 100644 index 0000000000..72d55c47bf --- /dev/null +++ b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc.py @@ -0,0 +1,145 @@ +# 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. + +"""Unitree G1 GR00T whole-body-control blueprint — real hardware. + +Runs the ControlCoordinator at 500 Hz with two tasks: + + - ``groot_wbc`` (priority 50) claims legs + waist (15 DOF) and runs + the GR00T balance / walk ONNX policies at 50 Hz. + - ``servo_arms`` (priority 10) claims the 14 arm joints and holds + them at the relaxed pose the policy was trained against. + +Real-hardware safety profile: the blueprint comes up unarmed and in +dry-run. The operator opens the dashboard at http://localhost:7779/, +verifies the computed commands look sane, then clicks Activate to +ramp from the current pose to the bent-knee default over 10 s before +handing torque control to the policy. + +Architecture: + dashboard WASD ──▶ WebsocketVisModule ──▶ LCM /g1/cmd_vel + │ + coordinator twist_command ──▶ GrootWBCTask + │ + ControlCoordinator ──joint_state──▶ LCM /coordinator/joint_state + ◀─joint_command── LCM /g1/joint_command + +Sim is a separate blueprint (``unitree-g1-groot-wbc-sim``) so each +file is statically clear about what it composes — no module-level +config branching. + +Usage: + ROBOT_INTERFACE=enp86s0 dimos run unitree-g1-groot-wbc + +Environment: + ROBOT_INTERFACE DDS network interface for the real robot + (default ``"enp86s0"``). + DIMOS_DDS_DOMAIN DDS domain id (default ``0``). + CYCLONEDDS_HOME Required at runtime — must point at the + cyclonedds C install (e.g. ``~/cyclonedds/install``). + GROOT_MODEL_DIR Directory containing ``balance.onnx`` + + ``walk.onnx`` (default: pulled via + ``get_data("groot")``). +""" + +from __future__ import annotations + +import os + +from dimos.control.components import HardwareComponent, HardwareType +from dimos.control.coordinator import ControlCoordinator, TaskConfig +from dimos.core.coordination.blueprints import autoconnect +from dimos.core.transport import LCMTransport +from dimos.hardware.whole_body.spec import WholeBodyConfig +from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped +from dimos.msgs.geometry_msgs.Twist import Twist +from dimos.msgs.sensor_msgs.JointState import JointState +from dimos.msgs.std_msgs.Bool import Bool as DimosBool +from dimos.robot.unitree.g1.blueprints.basic._groot_wbc_common import ( + ARM_DEFAULT_POSE, + G1_GROOT_KD, + G1_GROOT_KP, + g1_arms, + g1_joints, + g1_legs_waist, +) +from dimos.utils.data import get_data +from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule + +_g1_coordinator = ControlCoordinator.blueprint( + tick_rate=500.0, + publish_joint_state=True, + joint_state_frame_id="coordinator", + hardware=[ + HardwareComponent( + hardware_id="g1", + hardware_type=HardwareType.WHOLE_BODY, + joints=g1_joints, + adapter_type="unitree_g1", + address=os.getenv("ROBOT_INTERFACE", "enp86s0"), + domain_id=int(os.getenv("DIMOS_DDS_DOMAIN", "0")), + auto_enable=True, + wb_config=WholeBodyConfig(kp=tuple(G1_GROOT_KP), kd=tuple(G1_GROOT_KD)), + ), + ], + tasks=[ + TaskConfig( + name="groot_wbc", + type="groot_wbc", + joint_names=g1_legs_waist, + priority=50, + model_path=os.getenv("GROOT_MODEL_DIR", str(get_data("groot"))), + hardware_id="g1", + auto_start=True, + # Real-hw safety: come up unarmed + dry-run. Operator + # arms via the dashboard Activate button after sanity + # checks; activation ramps over 10 s. + auto_arm=False, + auto_dry_run=True, + default_ramp_seconds=10.0, + ), + TaskConfig( + name="servo_arms", + type="servo", + joint_names=g1_arms, + priority=10, + default_positions=ARM_DEFAULT_POSE, + auto_start=True, + ), + ], +).transports( + { + ("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState), + ("odom", PoseStamped): LCMTransport("/odom", PoseStamped), + ("joint_command", JointState): LCMTransport("/g1/joint_command", JointState), + ("twist_command", Twist): LCMTransport("/g1/cmd_vel", Twist), + ("activate", DimosBool): LCMTransport("/g1/activate", DimosBool), + ("dry_run", DimosBool): LCMTransport("/g1/dry_run", DimosBool), + } +) + +# Operator dashboard (WASD, Activate, dry-run toggle) at +# http://localhost:7779/. WebsocketVisModule re-publishes the +# dashboard's events onto the coordinator's LCM ports. +_g1_ws_vis = WebsocketVisModule.blueprint().transports( + { + ("cmd_vel", Twist): LCMTransport("/g1/cmd_vel", Twist), + ("activate", DimosBool): LCMTransport("/g1/activate", DimosBool), + ("dry_run", DimosBool): LCMTransport("/g1/dry_run", DimosBool), + }, +) + +unitree_g1_groot_wbc = autoconnect(_g1_coordinator, _g1_ws_vis) + +__all__ = ["unitree_g1_groot_wbc"] diff --git a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py new file mode 100644 index 0000000000..c340b004b4 --- /dev/null +++ b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py @@ -0,0 +1,124 @@ +# 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. + +"""Unitree G1 GR00T WBC blueprint — MuJoCo sim. + +Sim counterpart to ``unitree_g1_groot_wbc``. Same coordinator layout +(WHOLE_BODY g1 component + groot_wbc on legs+waist + servo_arms on +arms), only the WholeBodyAdapter swaps: sim_mujoco_g1 (SHM) instead +of unitree_g1 (DDS). Sim safety profile is laxer (auto_arm=True, +auto_dry_run=False) so the robot walks immediately. + +Usage: + dimos run unitree-g1-groot-wbc-sim +""" + +from __future__ import annotations + +from dimos.control.components import HardwareComponent, HardwareType +from dimos.control.coordinator import ControlCoordinator, TaskConfig +from dimos.core.coordination.blueprints import autoconnect +from dimos.core.transport import LCMTransport +from dimos.hardware.whole_body.spec import WholeBodyConfig +from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped +from dimos.msgs.geometry_msgs.Twist import Twist +from dimos.msgs.sensor_msgs.JointState import JointState +from dimos.msgs.std_msgs.Bool import Bool as DimosBool +from dimos.robot.unitree.g1.blueprints.basic._groot_wbc_common import ( + ARM_DEFAULT_POSE, + G1_GROOT_KD, + G1_GROOT_KP, + g1_arms, + g1_joints, + g1_legs_waist, +) +from dimos.simulation.engines.mujoco_sim_module import MujocoSimModule +from dimos.utils.data import get_data +from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule + +_MJCF_PATH = "data/mujoco_sim/g1_gear_wbc.xml" + +_g1_engine = MujocoSimModule.blueprint( + address=_MJCF_PATH, + headless=True, + dof=29, + enable_color=False, + enable_depth=False, + enable_pointcloud=False, + inject_legacy_assets=True, +).transports( + { + ("odom", PoseStamped): LCMTransport("/sim/odom", PoseStamped), + } +) + +_g1_coordinator = ControlCoordinator.blueprint( + tick_rate=500.0, + publish_joint_state=True, + joint_state_frame_id="coordinator", + hardware=[ + HardwareComponent( + hardware_id="g1", + hardware_type=HardwareType.WHOLE_BODY, + joints=g1_joints, + adapter_type="sim_mujoco_g1", + address=_MJCF_PATH, + auto_enable=True, + wb_config=WholeBodyConfig(kp=tuple(G1_GROOT_KP), kd=tuple(G1_GROOT_KD)), + ), + ], + tasks=[ + TaskConfig( + name="groot_wbc", + type="groot_wbc", + joint_names=g1_legs_waist, + priority=50, + model_path=str(get_data("groot")), + hardware_id="g1", + auto_start=True, + auto_arm=True, + auto_dry_run=False, + default_ramp_seconds=2.0, + ), + TaskConfig( + name="servo_arms", + type="servo", + joint_names=g1_arms, + priority=10, + default_positions=ARM_DEFAULT_POSE, + auto_start=True, + ), + ], +).transports( + { + ("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState), + ("odom", PoseStamped): LCMTransport("/odom", PoseStamped), + ("joint_command", JointState): LCMTransport("/g1/joint_command", JointState), + ("twist_command", Twist): LCMTransport("/g1/cmd_vel", Twist), + ("activate", DimosBool): LCMTransport("/g1/activate", DimosBool), + ("dry_run", DimosBool): LCMTransport("/g1/dry_run", DimosBool), + } +) + +_g1_ws_vis = WebsocketVisModule.blueprint().transports( + { + ("cmd_vel", Twist): LCMTransport("/g1/cmd_vel", Twist), + ("activate", DimosBool): LCMTransport("/g1/activate", DimosBool), + ("dry_run", DimosBool): LCMTransport("/g1/dry_run", DimosBool), + }, +) + +unitree_g1_groot_wbc_sim = autoconnect(_g1_engine, _g1_coordinator, _g1_ws_vis) + +__all__ = ["unitree_g1_groot_wbc_sim"] diff --git a/dimos/robot/unitree/g1/system_prompt.py b/dimos/robot/unitree/g1/system_prompt.py index 09acda3c16..b9060d28a2 100644 --- a/dimos/robot/unitree/g1/system_prompt.py +++ b/dimos/robot/unitree/g1/system_prompt.py @@ -53,6 +53,11 @@ - Tag important locations with `tag_location` so you can return to them later. - During `start_exploration`, avoid calling other skills except `stop_movement`. +## Object database (perception2) +- `list_objects` returns every object you've detected so far with its world position and observation count. Call this when asked "what have you seen?" or before deciding where to go. +- `find_object("query")` does a name search across the database — e.g. `find_object("flag")` returns matching entries. +- `goto_object("name")` sets a navigation goal at the object's center. The name must match what `list_objects` shows. + # BEHAVIOR Be proactive. Infer reasonable actions from ambiguous requests. Inform the user of your assumption. """ diff --git a/dimos/simulation/engines/mujoco_engine.py b/dimos/simulation/engines/mujoco_engine.py index ada85dd477..d16f218c20 100644 --- a/dimos/simulation/engines/mujoco_engine.py +++ b/dimos/simulation/engines/mujoco_engine.py @@ -48,6 +48,13 @@ class CameraConfig: width: int = 640 height: int = 480 fps: float = 15.0 + # Per-camera ``mjvOption`` applied during ``update_scene``. Lets a + # caller render the same scene through different geom-group masks + # — e.g. lidar cameras that should only see the static scene mesh + # (group 3) and ignore the robot (groups 0-2), so the lidar + # pointcloud doesn't pick up the robot's own hands/torso/legs as + # phantom obstacles. ``None`` keeps MuJoCo's default (all groups). + scene_option: mujoco.MjvOption | None = None @dataclass @@ -86,13 +93,22 @@ def __init__( cameras: list[CameraConfig] | None = None, on_before_step: StepHook | None = None, on_after_step: StepHook | None = None, + assets: dict[str, bytes] | None = None, ) -> None: super().__init__(config_path=config_path, headless=headless) self._on_before_step: StepHook | None = on_before_step 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)) + if assets is not None: + # MJCFs that reference meshes by bare filename (e.g. menagerie + # G1) need the mesh bytes injected by name; from_xml_path can't + # find them on disk. + with open(xml_path) as f: + xml_str = f.read() + self._model = mujoco.MjModel.from_xml_string(xml_str, assets=assets) + else: + self._model = mujoco.MjModel.from_xml_path(str(xml_path)) self._xml_path = xml_path self._data = mujoco.MjData(self._model) @@ -250,11 +266,21 @@ 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) - rgb = state.rgb_renderer.render().copy() - - state.depth_renderer.update_scene(self._data, camera=state.cam_id) - depth = state.depth_renderer.render().copy() + scene_option = state.cfg.scene_option + if scene_option is not None: + state.rgb_renderer.update_scene( + self._data, camera=state.cam_id, scene_option=scene_option + ) + rgb = state.rgb_renderer.render().copy() + state.depth_renderer.update_scene( + self._data, camera=state.cam_id, scene_option=scene_option + ) + depth = state.depth_renderer.render().copy() + else: + state.rgb_renderer.update_scene(self._data, camera=state.cam_id) + rgb = state.rgb_renderer.render().copy() + state.depth_renderer.update_scene(self._data, camera=state.cam_id) + depth = state.depth_renderer.render().copy() frame = CameraFrame( rgb=rgb, @@ -457,6 +483,24 @@ 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[np.ndarray, np.ndarray] | None: + """World pose of a named camera, regardless of whether it renders. + + Returns ``(cam_pos (3,), cam_mat (3, 3))`` from the latest physics + step. ``cam_xpos`` / ``cam_xmat`` are populated for every MJCF + camera at every step, so this works even when the camera isn't in + the ``cameras`` list passed to MujocoEngine — useful for publishing + TF for cameras that exist in the model purely as mount points + (e.g. head_color when only the lidar render is consumed). + """ + 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().reshape(3, 3), + ) + __all__ = [ "CameraConfig", diff --git a/dimos/simulation/engines/mujoco_shm.py b/dimos/simulation/engines/mujoco_shm.py index c0623c7915..54b63e965d 100644 --- a/dimos/simulation/engines/mujoco_shm.py +++ b/dimos/simulation/engines/mujoco_shm.py @@ -40,26 +40,38 @@ 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. Manipulators use ≤10; humanoids +# (Unitree G1: 29) push higher. 32 leaves headroom while keeping all +# per-joint buffers tiny (32 floats = 256 B). +MAX_JOINTS = 32 _FLOAT_BYTES = 8 # float64 _INT32_BYTES = 4 +# IMU layout: quat (4) + gyro (3) + accel (3) = 10 floats. +_IMU_FLOATS = 10 + _joint_array_size = MAX_JOINTS * _FLOAT_BYTES # float64 array # Element counts for control and sequence arrays. _NUM_CTRL_FIELDS = 4 # [ready, stop, command_mode, num_joints] -_NUM_SEQ_COUNTERS = 8 # one per buffer type +_NUM_SEQ_COUNTERS = 12 # one per buffer type (manipulator + WB additions) # Buffer sizes (in bytes). # Keys are short to stay under macOS PSHMNAMLEN (31 bytes). _shm_sizes = { + # Manipulator-shared layout "pos": _joint_array_size, "vel": _joint_array_size, "eff": _joint_array_size, "pos_t": _joint_array_size, "vel_t": _joint_array_size, "grp": 2 * _FLOAT_BYTES, # [gripper_position, gripper_target] + # Whole-body additions (unused by manipulator path). + "imu": _IMU_FLOATS * _FLOAT_BYTES, # [w,x,y,z, gx,gy,gz, ax,ay,az] + "kp_t": _joint_array_size, # per-joint position-gain target + "kd_t": _joint_array_size, # per-joint velocity-gain target + "tau_t": _joint_array_size, # per-joint feedforward torque + # Bookkeeping "seq": _NUM_SEQ_COUNTERS * _FLOAT_BYTES, # int64 counters "ctl": _NUM_CTRL_FIELDS * _INT32_BYTES, # [ready, stop, command_mode, num_joints] } @@ -72,6 +84,11 @@ SEQ_VELOCITY_CMD = 4 SEQ_GRIPPER_STATE = 5 SEQ_GRIPPER_CMD = 6 +# Whole-body additions +SEQ_IMU = 7 +SEQ_KP_CMD = 8 +SEQ_KD_CMD = 9 +SEQ_TAU_CMD = 10 # Control indices. CTRL_READY = 0 @@ -82,6 +99,9 @@ # Command modes. CMD_MODE_POSITION = 0 CMD_MODE_VELOCITY = 1 +# Whole-body PD-with-feedforward: ctrl = kp*(q_t - q) + kd*(0 - dq) + tau_t. +# Per-step kp/kd lets a policy retune gains online if it wants to. +CMD_MODE_PD_TAU = 2 _NAME_PREFIX = "dmjm" @@ -114,7 +134,13 @@ def _unregister(shm: SharedMemory) -> SharedMemory: @dataclass(frozen=True) class ManipShmSet: - """Frozen set of named SharedMemory buffers for manipulator IPC.""" + """Frozen set of named SharedMemory buffers for sim ↔ adapter IPC. + + Despite the name (kept for backward compat with existing manipulator + consumers), the layout now also covers whole-body needs: IMU, per-joint + PD gain commands, and per-joint feedforward torque commands. The + extra buffers are unused by the manipulator path. + """ pos: SharedMemory vel: SharedMemory @@ -122,6 +148,12 @@ class ManipShmSet: pos_t: SharedMemory vel_t: SharedMemory grp: SharedMemory + # Whole-body additions + imu: SharedMemory + kp_t: SharedMemory + kd_t: SharedMemory + tau_t: SharedMemory + # Bookkeeping seq: SharedMemory ctl: SharedMemory @@ -170,6 +202,9 @@ def __init__(self, key: str) -> None: self._last_pos_cmd_seq = 0 self._last_vel_cmd_seq = 0 self._last_gripper_cmd_seq = 0 + self._last_kp_cmd_seq = 0 + self._last_kd_cmd_seq = 0 + self._last_tau_cmd_seq = 0 # Zero everything. for buf in self.shm.as_list(): np.ndarray((buf.size,), dtype=np.uint8, buffer=buf.buf)[:] = 0 @@ -226,6 +261,47 @@ def read_gripper_command(self) -> float | None: def read_command_mode(self) -> int: return int(self._control()[CTRL_COMMAND_MODE]) + # --- Whole-body additions --- + + def write_imu( + self, + quaternion: tuple[float, float, float, float], + gyroscope: tuple[float, float, float], + accelerometer: tuple[float, float, float], + ) -> None: + """Write IMU sample. Quaternion is (w, x, y, z).""" + arr = self._array(self.shm.imu, _IMU_FLOATS, np.float64) + arr[0:4] = quaternion + arr[4:7] = gyroscope + arr[7:10] = accelerometer + self._increment_seq(SEQ_IMU) + + def read_kp_command(self, num_joints: int) -> NDArray[np.float64] | None: + """Per-joint position-gain target if a new command landed since last call.""" + seq = self._get_seq(SEQ_KP_CMD) + if seq <= self._last_kp_cmd_seq: + return None + self._last_kp_cmd_seq = seq + arr = self._array(self.shm.kp_t, MAX_JOINTS, np.float64) + return arr[:num_joints].copy() + + def read_kd_command(self, num_joints: int) -> NDArray[np.float64] | None: + seq = self._get_seq(SEQ_KD_CMD) + if seq <= self._last_kd_cmd_seq: + return None + self._last_kd_cmd_seq = seq + arr = self._array(self.shm.kd_t, MAX_JOINTS, np.float64) + return arr[:num_joints].copy() + + def read_tau_command(self, num_joints: int) -> NDArray[np.float64] | None: + """Per-joint feedforward torque if a new command landed since last call.""" + seq = self._get_seq(SEQ_TAU_CMD) + if seq <= self._last_tau_cmd_seq: + return None + self._last_tau_cmd_seq = seq + arr = self._array(self.shm.tau_t, MAX_JOINTS, np.float64) + return arr[:num_joints].copy() + def signal_ready(self, num_joints: int) -> None: ctrl = self._control() ctrl[CTRL_NUM_JOINTS] = num_joints @@ -314,6 +390,46 @@ def write_gripper_command(self, position: float) -> None: arr[1] = position self._increment_seq(SEQ_GRIPPER_CMD) + # --- Whole-body additions --- + + def read_imu( + self, + ) -> tuple[ + tuple[float, float, float, float], + tuple[float, float, float], + tuple[float, float, float], + ]: + """Read IMU sample: ((qw, qx, qy, qz), (gx, gy, gz), (ax, ay, az)).""" + arr = np.ndarray((_IMU_FLOATS,), dtype=np.float64, buffer=self.shm.imu.buf) + return ( + (float(arr[0]), float(arr[1]), float(arr[2]), float(arr[3])), + (float(arr[4]), float(arr[5]), float(arr[6])), + (float(arr[7]), float(arr[8]), float(arr[9])), + ) + + def write_kp_command(self, kp: list[float]) -> None: + """Per-joint position-gain target. Switches command mode to PD+τ.""" + n = min(len(kp), MAX_JOINTS) + arr = np.ndarray((MAX_JOINTS,), dtype=np.float64, buffer=self.shm.kp_t.buf) + arr[:n] = kp[:n] + self._set_command_mode(CMD_MODE_PD_TAU) + self._increment_seq(SEQ_KP_CMD) + + def write_kd_command(self, kd: list[float]) -> None: + n = min(len(kd), MAX_JOINTS) + arr = np.ndarray((MAX_JOINTS,), dtype=np.float64, buffer=self.shm.kd_t.buf) + arr[:n] = kd[:n] + self._set_command_mode(CMD_MODE_PD_TAU) + self._increment_seq(SEQ_KD_CMD) + + def write_tau_command(self, tau: list[float]) -> None: + """Per-joint feedforward torque, applied on top of PD.""" + n = min(len(tau), MAX_JOINTS) + arr = np.ndarray((MAX_JOINTS,), dtype=np.float64, buffer=self.shm.tau_t.buf) + arr[:n] = tau[:n] + self._set_command_mode(CMD_MODE_PD_TAU) + self._increment_seq(SEQ_TAU_CMD) + def is_ready(self) -> bool: return bool(self._control()[CTRL_READY] == 1) diff --git a/dimos/simulation/engines/mujoco_sim_module.py b/dimos/simulation/engines/mujoco_sim_module.py index 3d2ff927fe..cfe8476026 100644 --- a/dimos/simulation/engines/mujoco_sim_module.py +++ b/dimos/simulation/engines/mujoco_sim_module.py @@ -32,6 +32,9 @@ import time from typing import Any +import mujoco +import numpy as np +import open3d as o3d # type: ignore[import-untyped] from pydantic import Field import reactivex as rx from scipy.spatial.transform import Rotation as R @@ -40,19 +43,21 @@ from dimos.core.module import Module, ModuleConfig from dimos.core.stream import 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.Vector3 import Vector3 from dimos.msgs.sensor_msgs.CameraInfo import CameraInfo from dimos.msgs.sensor_msgs.Image import Image, ImageFormat +from dimos.msgs.sensor_msgs.Imu import Imu from dimos.msgs.sensor_msgs.JointState import JointState from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 from dimos.simulation.engines.mujoco_engine import ( CameraConfig, - CameraFrame, MujocoEngine, ) from dimos.simulation.engines.mujoco_shm import ( + CMD_MODE_PD_TAU, ManipShmWriter, shm_key_from_path, ) @@ -61,6 +66,17 @@ logger = setup_logger() + +def _find_sensor_slice(model: mujoco.MjModel, *names: str, dim: int = 3) -> slice | None: + """Return the first matching MJCF sensor's slice into sensordata, or None.""" + for n in names: + sid = mujoco.mj_name2id(model, mujoco.mjtObj.mjOBJ_SENSOR, n) + if sid >= 0: + adr = int(model.sensor_adr[sid]) + return slice(adr, adr + dim) + return None + + _RX180 = R.from_euler("x", 180, degrees=True) @@ -86,10 +102,30 @@ 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 + # Multi-camera lidar fusion. When non-empty, each camera in the + # list is rendered as a depth image, back-projected to world-frame + # points via depth_image_to_point_cloud(), and the union is + # voxel-downsampled before being published on `pointcloud`. This + # mirrors the legacy out-of-process mujoco_process.py behavior the + # Go2 sim has used since #862 — three 160°-FOV cameras stitched + # to a 360° scan so VoxelGridMapper's column-carving actually + # sees the same XY columns each frame and stops accumulating + # phantom obstacles behind a moving robot. When empty the + # original single-camera path runs unchanged. + 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 + # Inject menagerie/dimos-bundled mesh bytes (via + # dimos.simulation.mujoco.model.get_assets) into MjModel.from_xml_string. + # MJCFs that reference meshes by bare filename (G1 GR00T, Go2) need this; + # self-contained MJCFs with on-disk meshes (xarm scene.xml) don't. + inject_legacy_assets: bool = False class MujocoSimModule( @@ -111,6 +147,11 @@ class MujocoSimModule( pointcloud: Out[PointCloud2] camera_info: Out[CameraInfo] depth_camera_info: Out[CameraInfo] + imu: Out[Imu] + # Floating-base pose (qpos[0:7]) for robots whose MJCF has a free + # joint at the root. Published every step; consumers like the viser + # viewer use this to translate the robot in world space. + odom: Out[PoseStamped] def __init__(self, **kwargs: Any) -> None: super().__init__(**kwargs) @@ -123,6 +164,22 @@ def __init__(self, **kwargs: Any) -> None: self._publish_thread: threading.Thread | None = None self._camera_info_base: CameraInfo | None = None + # IMU sensor slices into MjData.sensordata, resolved once at start. + # None if the MJCF has no recognized IMU sensors (e.g. arm-only sims). + self._imu_gyro_slice: slice | None = None + self._imu_accel_slice: slice | None = None + # Quaternion is read from the floating-base qpos[3:7] when the model + # has a free joint at the root; None otherwise. + self._imu_base_qpos_slice: slice | None = None + + # Latched PD-with-feedforward command state. GR00T-style adapters + # write kp/kd/q_target every tick; we apply them to MjData.ctrl in + # the pre-step hook as tau = kp*(q_t - q) + kd*(0 - dq) + tau_ff. + self._latest_pd_pos_target: np.ndarray | None = None + self._latest_pd_kp: np.ndarray | None = None + self._latest_pd_kd: np.ndarray | None = None + self._latest_pd_tau: np.ndarray | None = None + @property def _camera_link(self) -> str: return f"{self.config.camera_name}_link" @@ -169,19 +226,71 @@ def start(self) -> None: 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=[ + engine_assets: dict[str, bytes] | None = None + if self.config.inject_legacy_assets: + from dimos.simulation.mujoco.model import get_assets + + engine_assets = get_assets() + # Compose the camera list. Each registered camera blocks the + # sim thread inside _step_once (mujoco_engine._render_cameras + # does update_scene + GPU render synchronously between physics + # steps — typically 5-30 ms per camera), so registering a camera + # nobody consumes burns the 500 Hz tick deadline for nothing. + # Skip the primary camera entirely when none of color / depth / + # pointcloud is enabled. Lidar cameras still register when + # `lidar_camera_names` is set. + cameras: 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: + cameras.append( CameraConfig( name=self.config.camera_name, width=self.config.width, height=self.config.height, fps=float(self.config.fps), ) - ], + ) + # Self-occlusion filter for the lidar cameras: only render the + # static scene mesh (group 3) and the floor (group 2 — see + # comment in g1_gear_wbc.xml) — hide the robot's own collision + # (group 0) and visual (group 1) meshes. Without this the + # lidar back-projects the robot's hands / torso / arms from the + # 3 torso-mounted cameras' POVs into the global voxel map, + # leaving a robot-shaped halo of phantom obstacles that travels + # with the robot and blocks A* from finding any path out. + lidar_scene_option = mujoco.MjvOption() + # MjvOption.geomgroup is a 6-byte array; default is all visible. + lidar_scene_option.geomgroup[0] = 0 # robot collision meshes + lidar_scene_option.geomgroup[1] = 0 # robot visual meshes + lidar_scene_option.geomgroup[2] = 1 # floor (kept visible) + lidar_scene_option.geomgroup[3] = 1 # scene-mesh convex hulls + 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 # already registered as the RGBD camera + cameras.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, + ) + ) + + self._engine = MujocoEngine( + config_path=Path(self.config.address), + headless=self.config.headless, + cameras=cameras, on_before_step=self._apply_shm_commands, on_after_step=self._publish_shm_state, + assets=engine_assets, ) # Detect gripper (extra joint beyond dof). @@ -202,6 +311,35 @@ def start(self) -> None: joint_range=joint_range, ) + # Resolve IMU sensors once. Whole-body MJCFs declare gyro/accel + # under various names; we accept the menagerie and dimos-bundled + # variants. Manipulator MJCFs typically have neither — we just + # leave the slices as None and skip IMU publishing for those. + self._imu_gyro_slice = _find_sensor_slice( + self._engine.model, + "imu-pelvis-angular-velocity", + "imu-torso-angular-velocity", + "gyro_pelvis", + "imu_gyro", + dim=3, + ) + self._imu_accel_slice = _find_sensor_slice( + self._engine.model, + "imu-pelvis-linear-acceleration", + "imu-torso-linear-acceleration", + "accelerometer_pelvis", + "imu_accel", + dim=3, + ) + # Floating-base orientation is qpos[3:7] (w,x,y,z) when the root + # joint is a free joint. Detect by checking jnt_type[0]. + if self._engine.model.njnt > 0 and int(self._engine.model.jnt_type[0]) == int( + mujoco.mjtJoint.mjJNT_FREE + ): + self._imu_base_qpos_slice = slice(3, 7) + else: + self._imu_base_qpos_slice = None + # Start physics (sim thread spawned inside engine.connect()). if not self._engine.connect(): raise RuntimeError("MujocoSimModule: engine.connect() failed") @@ -226,8 +364,14 @@ def start(self) -> None: ) ) - # Optional pointcloud generation. - if self.config.enable_pointcloud and self.config.enable_depth: + # Optional pointcloud generation. Two source modes: + # * Multi-camera lidar fusion (`lidar_camera_names` set) — each + # listed camera renders its own depth in the engine; we don't + # need `enable_depth` on the primary RGBD camera at all. + # * Single-camera fallback — back-projects the primary camera's + # depth image, so `enable_depth=True` IS required there. + _has_pointcloud_source = self.config.enable_depth or bool(self.config.lidar_camera_names) + if self.config.enable_pointcloud and _has_pointcloud_source: pc_interval = 1.0 / self.config.pointcloud_fps self.register_disposable( rx.interval(pc_interval).subscribe( @@ -284,12 +428,45 @@ def _apply_shm_commands(self, engine: MujocoEngine) -> None: pos_cmd = shm.read_position_command(dof) if pos_cmd is not None: - engine.write_joint_command(JointState(position=pos_cmd.tolist())) + if shm.read_command_mode() == CMD_MODE_PD_TAU: + # Latch position target for the per-step PD computation + # below; do NOT route through engine.write_joint_command + # (that would set position-mode and override our tau). + self._latest_pd_pos_target = pos_cmd + else: + engine.write_joint_command(JointState(position=pos_cmd.tolist())) vel_cmd = shm.read_velocity_command(dof) if vel_cmd is not None: engine.write_joint_command(JointState(velocity=vel_cmd.tolist())) + kp_cmd = shm.read_kp_command(dof) + if kp_cmd is not None: + self._latest_pd_kp = kp_cmd + kd_cmd = shm.read_kd_command(dof) + if kd_cmd is not None: + self._latest_pd_kd = kd_cmd + tau_cmd = shm.read_tau_command(dof) + if tau_cmd is not None: + self._latest_pd_tau = tau_cmd + + # Apply latched PD-tau if all four pieces have arrived at least once. + # Manipulator path (no kp/kd writes) skips this entirely. + if ( + self._latest_pd_pos_target is not None + and self._latest_pd_kp is not None + and self._latest_pd_kd is not None + ): + q = np.asarray(engine.joint_positions[:dof], dtype=np.float64) + dq = np.asarray(engine.joint_velocities[:dof], dtype=np.float64) + tau_ff = self._latest_pd_tau if self._latest_pd_tau is not None else np.zeros(dof) + tau = ( + self._latest_pd_kp * (self._latest_pd_pos_target - q) + + self._latest_pd_kd * (-dq) + + tau_ff + ) + engine.write_joint_command(JointState(effort=tau.tolist())) + if self._gripper_idx is not None: gripper_cmd = shm.read_gripper_command() if gripper_cmd is not None: @@ -297,7 +474,7 @@ def _apply_shm_commands(self, engine: MujocoEngine) -> None: engine.set_position_target(self._gripper_idx, ctrl_value) def _publish_shm_state(self, engine: MujocoEngine) -> None: - """Post-step hook: publish joint state to SHM.""" + """Post-step hook: publish joint state + IMU to SHM.""" shm = self._shm if shm is None: return @@ -311,6 +488,62 @@ def _publish_shm_state(self, engine: MujocoEngine) -> None: if self._gripper_idx < len(positions): shm.write_gripper_state(positions[self._gripper_idx]) + # Odom — when the MJCF has a free-joint root, publish base pose + # from qpos[0:7] every step. Without this, downstream consumers + # (viser viewer, nav stack) only see joint articulation, not + # base translation through the world. + data = engine._data # type: ignore[attr-defined] # in-process, same MjData + if self._imu_base_qpos_slice is not None: + base_pos = data.qpos[0:3] + base_quat = data.qpos[3:7] # (w, x, y, z) per MuJoCo convention + self.odom.publish( + PoseStamped( + ts=time.time(), + frame_id="world", + position=Vector3(float(base_pos[0]), float(base_pos[1]), float(base_pos[2])), + orientation=Quaternion( + float(base_quat[1]), + float(base_quat[2]), + float(base_quat[3]), + float(base_quat[0]), + ), # PoseStamped uses x,y,z,w + ) + ) + + # IMU — only if MJCF declared the sensors. + if ( + self._imu_gyro_slice is None + and self._imu_accel_slice is None + and self._imu_base_qpos_slice is None + ): + return + if self._imu_base_qpos_slice is not None: + q = data.qpos[self._imu_base_qpos_slice] + quat = (float(q[0]), float(q[1]), float(q[2]), float(q[3])) + else: + quat = (1.0, 0.0, 0.0, 0.0) + if self._imu_gyro_slice is not None: + g = data.sensordata[self._imu_gyro_slice] + gyro = (float(g[0]), float(g[1]), float(g[2])) + else: + gyro = (0.0, 0.0, 0.0) + if self._imu_accel_slice is not None: + a = data.sensordata[self._imu_accel_slice] + accel = (float(a[0]), float(a[1]), float(a[2])) + else: + accel = (0.0, 0.0, 0.0) + shm.write_imu(quaternion=quat, gyroscope=gyro, accelerometer=accel) + # Also publish on the stream port for downstream consumers. + self.imu.publish( + Imu( + ts=time.time(), + frame_id="pelvis", + orientation=Quaternion(quat[1], quat[2], quat[3], quat[0]), + angular_velocity=Vector3(gyro[0], gyro[1], gyro[2]), + linear_acceleration=Vector3(accel[0], accel[1], accel[2]), + ) + ) + def _gripper_joint_to_ctrl(self, joint_position: float) -> float: """Map joint-space gripper position to actuator control value.""" jlo, jhi = self._gripper_joint_range @@ -382,13 +615,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( @@ -399,7 +633,7 @@ def _publish_loop(self) -> None: ) self.depth_image.publish(depth_img) - self._publish_tf(ts, frame) + self._publish_tf(ts, frame.cam_pos, frame.cam_mat) published_count += 1 if published_count == 1: @@ -432,16 +666,14 @@ def _publish_camera_info(self) -> None: self.camera_info.publish(info) self.depth_camera_info.publish(info) - def _publish_tf(self, ts: float, frame: CameraFrame | None) -> None: - if frame is None: - return - mj_rot = R.from_matrix(frame.cam_mat.reshape(3, 3)) + def _publish_tf(self, ts: float, cam_pos: np.ndarray, cam_mat: np.ndarray) -> None: + mj_rot = R.from_matrix(cam_mat.reshape(3, 3)) optical_rot = mj_rot * _RX180 q = optical_rot.as_quat() # xyzw pos = Vector3( - float(frame.cam_pos[0]), - float(frame.cam_pos[1]), - float(frame.cam_pos[2]), + float(cam_pos[0]), + float(cam_pos[1]), + float(cam_pos[2]), ) rot = Quaternion(float(q[0]), float(q[1]), float(q[2]), float(q[3])) self.tf.publish( @@ -466,10 +698,80 @@ def _publish_tf(self, ts: float, frame: CameraFrame | None) -> None: child_frame_id=self._camera_link, ts=ts, ), + # Alias for Detection3DModule's hardcoded "camera_optical" + # target frame (perception/detection/module3D.py:181). Same + # pose as color_optical; lets the lidar-driven object DB do + # tf.get("camera_optical", "world", ts) without code changes. + Transform( + translation=pos, + rotation=rot, + frame_id="world", + child_frame_id="camera_optical", + ts=ts, + ), ) def _generate_pointcloud(self) -> None: - if self._engine is None or self._camera_info_base is None: + if self._engine is None: + return + # Multi-camera lidar fusion: render every named lidar camera, + # back-project each depth image into world frame, concatenate, + # and voxel-downsample. The result is a single 360° point cloud + # with `frame_id="world"`, which is what VoxelGridMapper expects + # ("Assumes input clouds are already in world frame."). This + # matches the legacy mujoco_process.py behavior the Go2 sim has + # always used. + if self.config.lidar_camera_names: + try: + from dimos.simulation.mujoco.depth_camera import depth_image_to_point_cloud + + all_points: list[np.ndarray] = [] + latest_ts: float = 0.0 + for cam_name in self.config.lidar_camera_names: + frame = self._engine.read_camera(cam_name) + if frame is None: + continue + # ``mj_data.cam_xmat`` is stored flat; the helper wants + # a 3x3. Don't .copy() — the engine already gave us a + # snapshot, just view it as the right shape. + cam_mat3 = np.asarray(frame.cam_mat, dtype=np.float64).reshape(3, 3) + pts = depth_image_to_point_cloud( + frame.depth, + frame.cam_pos, + cam_mat3, + fov_degrees=frame.fovy, + ) + if pts.size > 0: + all_points.append(pts) + latest_ts = max(latest_ts, frame.timestamp) + if not all_points: + return + combined = np.vstack(all_points) + pcd_o3d = o3d.geometry.PointCloud() + pcd_o3d.points = o3d.utility.Vector3dVector(combined) + pcd_o3d = pcd_o3d.voxel_down_sample(self.config.lidar_voxel_size) + self.pointcloud.publish( + PointCloud2(pointcloud=pcd_o3d, ts=latest_ts or time.time(), frame_id="world") + ) + # Publish head-camera TF here so consumers (ObjectDBModule, + # MeshCameraModule's TF lookups, etc.) see the optical + # frame even when ``enable_color`` / ``enable_depth`` are + # off and the camera-publish loop never registers + # head_color as a renderer. Pose comes from MjData + # directly — populated every physics step regardless of + # rendering, so no GPU work added. + pose = self._engine.get_camera_pose(self.config.camera_name) + if pose is not None: + cam_pos, cam_mat = pose + self._publish_tf(latest_ts or time.time(), cam_pos, cam_mat) + except Exception as exc: + logger.error("Multi-camera lidar fusion error", error=str(exc)) + return + + # Single-camera fallback: produce a camera-frame pointcloud from + # the primary RGBD camera. Kept for manipulation-style sims that + # want a head-camera depth feed instead of a 360° lidar. + if self._camera_info_base is None: return frame = self._engine.read_camera(self.config.camera_name) if frame is None: diff --git a/dimos/simulation/mujoco/model.py b/dimos/simulation/mujoco/model.py index bc309b7307..ac1713f090 100644 --- a/dimos/simulation/mujoco/model.py +++ b/dimos/simulation/mujoco/model.py @@ -42,6 +42,9 @@ def get_assets() -> dict[str, bytes]: # Assets used from https://sketchfab.com/3d-models/mersus-office-8714be387bcd406898b2615f7dae3a47 # Created by Ryan Cassidy and Coleman Costello mjx_env.update_assets(assets, data_dir, "*.xml") + mjx_env.update_assets( + assets, data_dir, "*.obj" + ) # top-level scene meshes (e.g. dimos_office.obj) mjx_env.update_assets(assets, data_dir / "scene_office1/textures", "*.png") mjx_env.update_assets(assets, data_dir / "scene_office1/office_split", "*.obj") mjx_env.update_assets(assets, mjx_env.MENAGERIE_PATH / "unitree_go1" / "assets") @@ -56,8 +59,19 @@ def get_assets() -> dict[str, bytes]: def load_model( - input_device: InputController, robot: str, scene_xml: str + input_device: InputController, + robot: str, + scene_xml: str, + skip_controller: bool = False, ) -> tuple[mujoco.MjModel, mujoco.MjData]: + """Load a MuJoCo model + data for ``robot`` inside ``scene_xml``. + + When ``skip_controller=True``, the baked-in ONNX locomotion policy is + NOT installed as the MuJoCo control callback. Used by low-level + passthrough mode where an external caller (e.g. the dimos + ControlCoordinator via shared memory) drives ``data.ctrl`` each + tick. + """ mujoco.set_mjcb_control(None) xml_string = get_model_xml(robot, scene_xml) @@ -76,6 +90,9 @@ def load_model( n_substeps = round(ctrl_dt / sim_dt) model.opt.timestep = sim_dt + if skip_controller: + return model, data + params = { "policy_path": (_get_data_dir() / f"{robot}_policy.onnx").as_posix(), "default_angles": np.array(model.keyframe("home").qpos[7:]), diff --git a/pyproject.toml b/pyproject.toml index 630b1e578c..c243502933 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -54,7 +54,7 @@ dependencies = [ # Core "numpy>=1.26.4", "scipy>=1.15.1", - "pin>=3.3.0", # Pinocchio IK library + "pin>=3.3.0", # Pinocchio IK library "reactivex", "sortedcontainers==2.4.0", "pydantic", @@ -77,12 +77,16 @@ dependencies = [ "typer>=0.19.2,<1", "plotext==5.3.2", # Used for calculating the occupancy map. - "numba>=0.60.0", # First version supporting Python 3.12 + "numba>=0.60.0", # First version supporting Python 3.12 "llvmlite>=0.42.0", # Required by numba 0.60+ # TODO: rerun shouldn't be required but rn its in core (there is NO WAY to use dimos without rerun rn) # remove this once rerun is optional in core - "rerun-sdk>=0.20.0", - "dimos-viewer>=0.30.0a2", + # Pinned to 0.30.x so rerun-sdk and dimos-viewer (which is a fork of + # rerun's 0.30 series) speak the same gRPC wire format. Allowing + # rerun-sdk 0.31+ produces a port mismatch (SDK→9876 vs viewer→9877) + # that crashes RerunBridge at startup. + "rerun-sdk>=0.30,<0.31", + "dimos-viewer>=0.30.0a2,<0.31", "toolz>=1.1.0", "protobuf>=6.33.5,<7", "psutil>=7.0.0", @@ -153,8 +157,8 @@ misc = [ ] visualization = [ - "rerun-sdk>=0.20.0", - "dimos-viewer>=0.30.0a4", + "rerun-sdk>=0.30,<0.31", + "dimos-viewer>=0.30.0a4,<0.31", ] agents = [ @@ -196,7 +200,7 @@ perception = [ unitree = [ "dimos[base]", - "unitree-webrtc-connect-leshy>=2.0.7" + "unitree-webrtc-connect-leshy>=2.0.7", ] unitree-dds = [ @@ -297,6 +301,28 @@ sim = [ "mujoco>=3.3.4", "playground>=0.0.5", "pygame>=2.6.1", + # USD/USDZ scene-mesh loader (used by dimos.mapping.mesh_scene for + # MeshCameraModule + bake_scene_mjcf collision wrapping). + "usd-core>=24.0", +] + +# Viser browser viewer + Gaussian splat scene loader. Opt-in. +# Required by ViserRenderModule (browser viewer at :8082) and by the +# splat loader used by both the viewer and the splat camera renderer. +viz = [ + "viser>=1.0.26", + "plyfile>=1.1.3", +] + +# 3D Gaussian splat camera renderer (Linux+CUDA only). Opt-in. +# gsplat builds CUDA kernels via nvcc/ninja on first import; first-time +# install is slow. Required only by the SplatCameraModule that +# publishes splat-rendered camera images. Pulls in [viz] for the splat +# loader. +splat = [ + "dimos[viz]", + "gsplat>=1.5.0", + "gsplat>=1.5.0; platform_machine == 'x86_64' and sys_platform == 'linux'", ] # NOTE: jetson-jp6-cuda126 extra is disabled due to 404 errors from wheel URLs @@ -465,6 +491,8 @@ concurrency = ["multiprocessing", "thread"] show_missing = true skip_empty = true +[tool.uv.sources] + [tool.largefiles] max_size_kb = 50 ignore = [ @@ -473,4 +501,5 @@ ignore = [ "dimos/dashboard/dimos.rbl", "dimos/web/dimos_interface/themes.json", "dimos/manipulation/manipulation_module.py", + "dimos/manipulation/planning/world/drake_world.py", ] diff --git a/uv.lock b/uv.lock index 6e94931740..9a72f9ede0 100644 --- a/uv.lock +++ b/uv.lock @@ -1,5 +1,5 @@ version = 1 -revision = 2 +revision = 3 requires-python = ">=3.10" resolution-markers = [ "python_full_version >= '3.14' and sys_platform == 'darwin'", @@ -10,18 +10,23 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] [[package]] @@ -495,7 +500,7 @@ name = "build" version = "1.4.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "colorama", marker = "(os_name == 'nt' and platform_machine != 'aarch64' and sys_platform == 'linux') or (os_name == 'nt' and sys_platform != 'darwin' and sys_platform != 'linux')" }, + { name = "colorama", marker = "(os_name == 'nt' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (os_name == 'nt' and sys_platform != 'darwin' and sys_platform != 'linux')" }, { name = "importlib-metadata", marker = "python_full_version < '3.10.2'" }, { name = "packaging" }, { name = "pyproject-hooks" }, @@ -750,7 +755,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "absl-py", marker = "python_full_version < '3.11'" }, @@ -778,14 +784,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "absl-py", marker = "python_full_version >= '3.11'" }, @@ -1166,7 +1176,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, @@ -1244,14 +1255,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, @@ -1530,7 +1545,7 @@ name = "cuda-bindings" version = "12.9.4" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "cuda-pathfinder", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, + { name = "cuda-pathfinder", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/7a/d8/b546104b8da3f562c1ff8ab36d130c8fe1dd6a045ced80b4f6ad74f7d4e1/cuda_bindings-12.9.4-cp310-cp310-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4d3c842c2a4303b2a580fe955018e31aea30278be19795ae05226235268032e5", size = 12148218, upload-time = "2025-10-21T14:51:28.855Z" }, @@ -1897,6 +1912,12 @@ sim = [ { name = "mujoco" }, { name = "playground" }, { name = "pygame" }, + { name = "usd-core" }, +] +splat = [ + { name = "gsplat" }, + { name = "plyfile" }, + { name = "viser" }, ] unitree = [ { name = "anthropic" }, @@ -1966,6 +1987,10 @@ visualization = [ { name = "dimos-viewer" }, { name = "rerun-sdk" }, ] +viz = [ + { name = "plyfile" }, + { name = "viser" }, +] web = [ { name = "fastapi" }, { name = "ffmpeg-python" }, @@ -1991,10 +2016,11 @@ requires-dist = [ { name = "dimos", extras = ["agents", "web", "perception", "visualization"], marker = "extra == 'base'" }, { name = "dimos", extras = ["base"], marker = "extra == 'unitree'" }, { name = "dimos", extras = ["unitree"], marker = "extra == 'unitree-dds'" }, + { name = "dimos", extras = ["viz"], marker = "extra == 'splat'" }, { name = "dimos-lcm" }, { name = "dimos-lcm", marker = "extra == 'docker'" }, - { name = "dimos-viewer", specifier = ">=0.30.0a2" }, - { name = "dimos-viewer", marker = "extra == 'visualization'", specifier = ">=0.30.0a4" }, + { name = "dimos-viewer", specifier = ">=0.30.0a2,<0.31" }, + { name = "dimos-viewer", marker = "extra == 'visualization'", specifier = ">=0.30.0a4,<0.31" }, { name = "drake", marker = "platform_machine != 'aarch64' and sys_platform == 'darwin' and extra == 'manipulation'", specifier = "==1.45.0" }, { name = "drake", marker = "platform_machine != 'aarch64' and sys_platform != 'darwin' and extra == 'manipulation'", specifier = ">=1.40.0" }, { name = "edgetam-dimos", marker = "extra == 'misc'" }, @@ -2005,6 +2031,8 @@ requires-dist = [ { name = "filterpy", marker = "extra == 'perception'", specifier = ">=1.4.5" }, { name = "gdown", marker = "extra == 'misc'", specifier = "==5.2.0" }, { name = "googlemaps", marker = "extra == 'misc'", specifier = ">=4.10.0" }, + { name = "gsplat", marker = "platform_machine == 'x86_64' and sys_platform == 'linux' and extra == 'splat'", specifier = ">=1.5.0" }, + { name = "gsplat", marker = "extra == 'splat'", specifier = ">=1.5.0" }, { name = "hydra-core", marker = "extra == 'perception'", specifier = ">=1.3.0" }, { name = "ipykernel", marker = "extra == 'misc'" }, { name = "kaleido", marker = "extra == 'manipulation'", specifier = ">=0.2.1" }, @@ -2055,6 +2083,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" }, @@ -2084,9 +2113,9 @@ requires-dist = [ { name = "reactivex", marker = "extra == 'docker'" }, { name = "requests", marker = "extra == 'docker'", specifier = ">=2.28" }, { name = "requests-mock", marker = "extra == 'dev'", specifier = "==1.12.1" }, - { name = "rerun-sdk", specifier = ">=0.20.0" }, + { name = "rerun-sdk", specifier = ">=0.30,<0.31" }, { name = "rerun-sdk", marker = "extra == 'docker'" }, - { name = "rerun-sdk", marker = "extra == 'visualization'", specifier = ">=0.20.0" }, + { name = "rerun-sdk", marker = "extra == 'visualization'", specifier = ">=0.30,<0.31" }, { name = "rpyc", specifier = ">=6.0.0" }, { name = "ruff", marker = "extra == 'dev'", specifier = "==0.14.3" }, { name = "scikit-learn", marker = "extra == 'misc'" }, @@ -2137,7 +2166,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" }, @@ -2145,7 +2176,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", "drone", "dds", "docker", "base"] +provides-extras = ["misc", "visualization", "agents", "web", "perception", "unitree", "unitree-dds", "manipulation", "cpu", "cuda", "dev", "psql", "sim", "viz", "splat", "drone", "dds", "docker", "base"] [[package]] name = "dimos-lcm" @@ -2267,14 +2298,19 @@ source = { registry = "https://pypi.org/simple" } resolution-markers = [ "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "matplotlib", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux')" }, @@ -2374,6 +2410,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 != 'aarch64') or (python_full_version < '3.11' and sys_platform != 'linux')" }, + { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "(python_full_version >= '3.11' and platform_machine != 'aarch64') or (python_full_version >= '3.11' and sys_platform != 'linux')" }, +] +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" @@ -2694,7 +2759,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "jax", version = "0.6.2", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, @@ -2725,14 +2791,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "jax", version = "0.9.0.1", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, @@ -3015,6 +3085,23 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/48/b2/b096ccce418882fbfda4f7496f9357aaa9a5af1896a9a7f60d9f2b275a06/grpcio-1.78.0-cp314-cp314-win_amd64.whl", hash = "sha256:dce09d6116df20a96acfdbf85e4866258c3758180e8c49845d6ba8248b6d0bbb", size = 4929852, upload-time = "2026-02-06T09:56:45.885Z" }, ] +[[package]] +name = "gsplat" +version = "1.5.3" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "jaxtyping" }, + { name = "ninja" }, + { 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 = "rich" }, + { name = "torch" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/6d/94/a0963873708223385ac926112dc3e40ab08297784ac53d95309b4cb5a801/gsplat-1.5.3.tar.gz", hash = "sha256:343f080c470e891ba3c697c03bdf0952cb982d1d535fdc24adb23c2cb4fba906", size = 4743603, upload-time = "2025-07-04T16:50:42.899Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/aa/68/c5cbbdb86421a3f45ac0b52cf9860b1048d089335151d3f37c23aabcbef1/gsplat-1.5.3-py3-none-any.whl", hash = "sha256:515a3773641f5e7f7717acab6276c0b1d6dbcad087b7968ca653337c3189a982", size = 6519041, upload-time = "2025-07-04T16:50:40.559Z" }, +] + [[package]] name = "h11" version = "0.16.0" @@ -3229,6 +3316,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" @@ -3303,7 +3404,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "colorama", marker = "python_full_version < '3.11' and sys_platform == 'win32'" }, @@ -3336,14 +3438,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "colorama", marker = "python_full_version >= '3.11' and sys_platform == 'win32'" }, @@ -3401,7 +3507,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "jaxlib", version = "0.6.2", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, @@ -3428,14 +3535,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "jaxlib", version = "0.9.0.1", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, @@ -3457,7 +3568,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "ml-dtypes", marker = "python_full_version < '3.11'" }, @@ -3498,14 +3610,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "ml-dtypes", marker = "python_full_version >= '3.11'" }, @@ -3561,7 +3677,7 @@ name = "jaxtyping" version = "0.3.7" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "wadler-lindig", marker = "python_full_version >= '3.11'" }, + { name = "wadler-lindig" }, ] sdist = { url = "https://files.pythonhosted.org/packages/38/40/a2ea3ce0e3e5f540eb970de7792c90fa58fef1b27d34c83f9fa94fea4729/jaxtyping-0.3.7.tar.gz", hash = "sha256:3bd7d9beb7d3cb01a89f93f90581c6f4fff3e5c5dc3c9307e8f8687a040d10c4", size = 45721, upload-time = "2026-01-30T14:18:47.409Z" } wheels = [ @@ -4590,6 +4706,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" @@ -5077,14 +5305,19 @@ source = { registry = "https://pypi.org/simple" } resolution-markers = [ "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux')" }, @@ -5166,6 +5399,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" @@ -5319,7 +5608,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] sdist = { url = "https://files.pythonhosted.org/packages/fd/1d/06475e1cd5264c0b870ea2cc6fdb3e37177c1e565c43f56ff17a10e3937f/networkx-3.4.2.tar.gz", hash = "sha256:307c3669428c5362aab27c8a1260aa8f47c4e91d3891f48be0141738d8d053e1", size = 2151368, upload-time = "2024-10-21T12:39:38.695Z" } wheels = [ @@ -5339,20 +5629,50 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] sdist = { url = "https://files.pythonhosted.org/packages/6a/51/63fe664f3908c97be9d2e4f1158eb633317598cfa6e1fc14af5383f17512/networkx-3.6.1.tar.gz", hash = "sha256:26b7c357accc0c8cde558ad486283728b65b6a95d85ee1cd66bafab4c8168509", size = 2517025, upload-time = "2025-12-08T17:02:39.908Z" } wheels = [ { url = "https://files.pythonhosted.org/packages/9e/c9/b2622292ea83fbb4ec318f5b9ab867d0a28ab43c5717bb85b0a5f6b3b0a4/networkx-3.6.1-py3-none-any.whl", hash = "sha256:d47fbf302e7d9cbbb9e2555a0d267983d2aa476bac30e90dfbe5669bd57f3762", size = 2068504, upload-time = "2025-12-08T17:02:38.159Z" }, ] +[[package]] +name = "ninja" +version = "1.13.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/43/73/79a0b22fc731989c708068427579e840a6cf4e937fe7ae5c5d0b7356ac22/ninja-1.13.0.tar.gz", hash = "sha256:4a40ce995ded54d9dc24f8ea37ff3bf62ad192b547f6c7126e7e25045e76f978", size = 242558, upload-time = "2025-08-11T15:10:19.421Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/3c/74/d02409ed2aa865e051b7edda22ad416a39d81a84980f544f8de717cab133/ninja-1.13.0-py3-none-macosx_10_9_universal2.whl", hash = "sha256:fa2a8bfc62e31b08f83127d1613d10821775a0eb334197154c4d6067b7068ff1", size = 310125, upload-time = "2025-08-11T15:09:50.971Z" }, + { url = "https://files.pythonhosted.org/packages/8e/de/6e1cd6b84b412ac1ef327b76f0641aeb5dcc01e9d3f9eee0286d0c34fd93/ninja-1.13.0-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:3d00c692fb717fd511abeb44b8c5d00340c36938c12d6538ba989fe764e79630", size = 177467, upload-time = "2025-08-11T15:09:52.767Z" }, + { url = "https://files.pythonhosted.org/packages/c8/83/49320fb6e58ae3c079381e333575fdbcf1cca3506ee160a2dcce775046fa/ninja-1.13.0-py3-none-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:be7f478ff9f96a128b599a964fc60a6a87b9fa332ee1bd44fa243ac88d50291c", size = 187834, upload-time = "2025-08-11T15:09:54.115Z" }, + { url = "https://files.pythonhosted.org/packages/56/c7/ba22748fb59f7f896b609cd3e568d28a0a367a6d953c24c461fe04fc4433/ninja-1.13.0-py3-none-manylinux2014_ppc64le.manylinux_2_17_ppc64le.whl", hash = "sha256:60056592cf495e9a6a4bea3cd178903056ecb0943e4de45a2ea825edb6dc8d3e", size = 202736, upload-time = "2025-08-11T15:09:55.745Z" }, + { url = "https://files.pythonhosted.org/packages/79/22/d1de07632b78ac8e6b785f41fa9aad7a978ec8c0a1bf15772def36d77aac/ninja-1.13.0-py3-none-manylinux2014_s390x.manylinux_2_17_s390x.whl", hash = "sha256:1c97223cdda0417f414bf864cfb73b72d8777e57ebb279c5f6de368de0062988", size = 179034, upload-time = "2025-08-11T15:09:57.394Z" }, + { url = "https://files.pythonhosted.org/packages/ed/de/0e6edf44d6a04dabd0318a519125ed0415ce437ad5a1ec9b9be03d9048cf/ninja-1.13.0-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:fb46acf6b93b8dd0322adc3a4945452a4e774b75b91293bafcc7b7f8e6517dfa", size = 180716, upload-time = "2025-08-11T15:09:58.696Z" }, + { url = "https://files.pythonhosted.org/packages/54/28/938b562f9057aaa4d6bfbeaa05e81899a47aebb3ba6751e36c027a7f5ff7/ninja-1.13.0-py3-none-manylinux_2_28_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:4be9c1b082d244b1ad7ef41eb8ab088aae8c109a9f3f0b3e56a252d3e00f42c1", size = 146843, upload-time = "2025-08-11T15:10:00.046Z" }, + { url = "https://files.pythonhosted.org/packages/2a/fb/d06a3838de4f8ab866e44ee52a797b5491df823901c54943b2adb0389fbb/ninja-1.13.0-py3-none-manylinux_2_31_riscv64.whl", hash = "sha256:6739d3352073341ad284246f81339a384eec091d9851a886dfa5b00a6d48b3e2", size = 154402, upload-time = "2025-08-11T15:10:01.657Z" }, + { url = "https://files.pythonhosted.org/packages/31/bf/0d7808af695ceddc763cf251b84a9892cd7f51622dc8b4c89d5012779f06/ninja-1.13.0-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:11be2d22027bde06f14c343f01d31446747dbb51e72d00decca2eb99be911e2f", size = 552388, upload-time = "2025-08-11T15:10:03.349Z" }, + { url = "https://files.pythonhosted.org/packages/9d/70/c99d0c2c809f992752453cce312848abb3b1607e56d4cd1b6cded317351a/ninja-1.13.0-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:aa45b4037b313c2f698bc13306239b8b93b4680eb47e287773156ac9e9304714", size = 472501, upload-time = "2025-08-11T15:10:04.735Z" }, + { url = "https://files.pythonhosted.org/packages/9f/43/c217b1153f0e499652f5e0766da8523ce3480f0a951039c7af115e224d55/ninja-1.13.0-py3-none-musllinux_1_2_i686.whl", hash = "sha256:5f8e1e8a1a30835eeb51db05cf5a67151ad37542f5a4af2a438e9490915e5b72", size = 638280, upload-time = "2025-08-11T15:10:06.512Z" }, + { url = "https://files.pythonhosted.org/packages/8c/45/9151bba2c8d0ae2b6260f71696330590de5850e5574b7b5694dce6023e20/ninja-1.13.0-py3-none-musllinux_1_2_ppc64le.whl", hash = "sha256:3d7d7779d12cb20c6d054c61b702139fd23a7a964ec8f2c823f1ab1b084150db", size = 642420, upload-time = "2025-08-11T15:10:08.35Z" }, + { url = "https://files.pythonhosted.org/packages/3c/fb/95752eb635bb8ad27d101d71bef15bc63049de23f299e312878fc21cb2da/ninja-1.13.0-py3-none-musllinux_1_2_riscv64.whl", hash = "sha256:d741a5e6754e0bda767e3274a0f0deeef4807f1fec6c0d7921a0244018926ae5", size = 585106, upload-time = "2025-08-11T15:10:09.818Z" }, + { url = "https://files.pythonhosted.org/packages/c1/31/aa56a1a286703800c0cbe39fb4e82811c277772dc8cd084f442dd8e2938a/ninja-1.13.0-py3-none-musllinux_1_2_s390x.whl", hash = "sha256:e8bad11f8a00b64137e9b315b137d8bb6cbf3086fbdc43bf1f90fd33324d2e96", size = 707138, upload-time = "2025-08-11T15:10:11.366Z" }, + { url = "https://files.pythonhosted.org/packages/34/6f/5f5a54a1041af945130abdb2b8529cbef0cdcbbf9bcf3f4195378319d29a/ninja-1.13.0-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:b4f2a072db3c0f944c32793e91532d8948d20d9ab83da9c0c7c15b5768072200", size = 581758, upload-time = "2025-08-11T15:10:13.295Z" }, + { url = "https://files.pythonhosted.org/packages/95/97/51359c77527d45943fe7a94d00a3843b81162e6c4244b3579fe8fc54cb9c/ninja-1.13.0-py3-none-win32.whl", hash = "sha256:8cfbb80b4a53456ae8a39f90ae3d7a2129f45ea164f43fadfa15dc38c4aef1c9", size = 267201, upload-time = "2025-08-11T15:10:15.158Z" }, + { url = "https://files.pythonhosted.org/packages/29/45/c0adfbfb0b5895aa18cec400c535b4f7ff3e52536e0403602fc1a23f7de9/ninja-1.13.0-py3-none-win_amd64.whl", hash = "sha256:fb8ee8719f8af47fed145cced4a85f0755dd55d45b2bddaf7431fa89803c5f3e", size = 309975, upload-time = "2025-08-11T15:10:16.697Z" }, + { url = "https://files.pythonhosted.org/packages/df/93/a7b983643d1253bb223234b5b226e69de6cda02b76cdca7770f684b795f5/ninja-1.13.0-py3-none-win_arm64.whl", hash = "sha256:3c0b40b1f0bba764644385319028650087b4c1b18cdfa6f45cb39a3669b81aa9", size = 290806, upload-time = "2025-08-11T15:10:18.018Z" }, +] + [[package]] name = "nodeenv" version = "1.10.0" @@ -5403,7 +5723,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] sdist = { url = "https://files.pythonhosted.org/packages/76/21/7d2a95e4bba9dc13d043ee156a356c0a8f0c6309dff6b21b4d71a073b8a8/numpy-2.2.6.tar.gz", hash = "sha256:e29554e2bef54a90aa5cc07da6ce955accb83f21ab5de01a62c8478897b264fd", size = 20276440, upload-time = "2025-05-17T22:38:04.611Z" } wheels = [ @@ -5476,14 +5797,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] sdist = { url = "https://files.pythonhosted.org/packages/76/65/21b3bc86aac7b8f2862db1e808f1ea22b028e30a225a34a5ede9bf8678f2/numpy-2.3.5.tar.gz", hash = "sha256:784db1dcdab56bf0517743e746dfb0f885fc68d948aba86eeec2cba234bdf1c0", size = 20584950, upload-time = "2025-11-16T22:52:42.067Z" } wheels = [ @@ -5579,11 +5904,16 @@ name = "nvidia-cublas-cu12" version = "12.8.4.1" source = { registry = "https://pypi.org/simple" } resolution-markers = [ - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] wheels = [ { url = "https://files.pythonhosted.org/packages/29/99/db44d685f0e257ff0e213ade1964fc459b4a690a73293220e98feb3307cf/nvidia_cublas_cu12-12.8.4.1-py3-none-manylinux_2_27_aarch64.whl", hash = "sha256:b86f6dd8935884615a0683b663891d43781b819ac4f2ba2b0c9604676af346d0", size = 590537124, upload-time = "2025-03-07T01:43:53.556Z" }, @@ -5613,7 +5943,6 @@ resolution-markers = [ ] wheels = [ { url = "https://files.pythonhosted.org/packages/82/6c/90d3f532f608a03a13c1d6c16c266ffa3828e8011b1549d3b61db2ad59f5/nvidia_cublas_cu12-12.9.1.4-py3-none-manylinux_2_27_aarch64.whl", hash = "sha256:7a950dae01add3b415a5a5cdc4ec818fb5858263e9cca59004bb99fdbbd3a5d6", size = 575006342, upload-time = "2025-06-05T20:04:16.902Z" }, - { url = "https://files.pythonhosted.org/packages/77/3c/aa88abe01f3be3d1f8f787d1d33dc83e76fec05945f9a28fbb41cfb99cd5/nvidia_cublas_cu12-12.9.1.4-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:453611eb21a7c1f2c2156ed9f3a45b691deda0440ec550860290dc901af5b4c2", size = 581242350, upload-time = "2025-06-05T20:04:51.979Z" }, { url = "https://files.pythonhosted.org/packages/45/a1/a17fade6567c57452cfc8f967a40d1035bb9301db52f27808167fbb2be2f/nvidia_cublas_cu12-12.9.1.4-py3-none-win_amd64.whl", hash = "sha256:1e5fee10662e6e52bd71dec533fbbd4971bb70a5f24f3bc3793e5c2e9dc640bf", size = 553153899, upload-time = "2025-06-05T20:13:35.556Z" }, ] @@ -5638,11 +5967,16 @@ name = "nvidia-cuda-runtime-cu12" version = "12.8.90" source = { registry = "https://pypi.org/simple" } resolution-markers = [ - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] wheels = [ { url = "https://files.pythonhosted.org/packages/7c/75/f865a3b236e4647605ea34cc450900854ba123834a5f1598e160b9530c3a/nvidia_cuda_runtime_cu12-12.8.90-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:52bf7bbee900262ffefe5e9d5a2a69a30d97e2bc5bb6cc866688caa976966e3d", size = 965265, upload-time = "2025-03-07T01:39:43.533Z" }, @@ -5672,7 +6006,6 @@ resolution-markers = [ ] wheels = [ { url = "https://files.pythonhosted.org/packages/bc/e0/0279bd94539fda525e0c8538db29b72a5a8495b0c12173113471d28bce78/nvidia_cuda_runtime_cu12-12.9.79-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:83469a846206f2a733db0c42e223589ab62fd2fabac4432d2f8802de4bded0a4", size = 3515012, upload-time = "2025-06-05T20:00:35.519Z" }, - { url = "https://files.pythonhosted.org/packages/bc/46/a92db19b8309581092a3add7e6fceb4c301a3fd233969856a8cbf042cd3c/nvidia_cuda_runtime_cu12-12.9.79-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:25bba2dfb01d48a9b59ca474a1ac43c6ebf7011f1b0b8cc44f54eb6ac48a96c3", size = 3493179, upload-time = "2025-06-05T20:00:53.735Z" }, { url = "https://files.pythonhosted.org/packages/59/df/e7c3a360be4f7b93cee39271b792669baeb3846c58a4df6dfcf187a7ffab/nvidia_cuda_runtime_cu12-12.9.79-py3-none-win_amd64.whl", hash = "sha256:8e018af8fa02363876860388bd10ccb89eb9ab8fb0aa749aaf58430a9f7c4891", size = 3591604, upload-time = "2025-06-05T20:11:17.036Z" }, ] @@ -5681,7 +6014,7 @@ name = "nvidia-cudnn-cu12" version = "9.10.2.21" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-cublas-cu12", version = "12.8.4.1", source = { registry = "https://pypi.org/simple" }, marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, + { name = "nvidia-cublas-cu12", version = "12.8.4.1", source = { registry = "https://pypi.org/simple" }, marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/ba/51/e123d997aa098c61d029f76663dedbfb9bc8dcf8c60cbd6adbe42f76d049/nvidia_cudnn_cu12-9.10.2.21-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:949452be657fa16687d0930933f032835951ef0892b37d2d53824d1a84dc97a8", size = 706758467, upload-time = "2025-06-06T21:54:08.597Z" }, @@ -5692,7 +6025,7 @@ name = "nvidia-cufft-cu12" version = "11.3.3.83" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-nvjitlink-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, + { name = "nvidia-nvjitlink-cu12", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/1f/13/ee4e00f30e676b66ae65b4f08cb5bcbb8392c03f54f2d5413ea99a5d1c80/nvidia_cufft_cu12-11.3.3.83-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:4d2dd21ec0b88cf61b62e6b43564355e5222e4a3fb394cac0db101f2dd0d4f74", size = 193118695, upload-time = "2025-03-07T01:45:27.821Z" }, @@ -5719,9 +6052,9 @@ name = "nvidia-cusolver-cu12" version = "11.7.3.90" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-cublas-cu12", version = "12.8.4.1", source = { registry = "https://pypi.org/simple" }, marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, - { name = "nvidia-cusparse-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, - { name = "nvidia-nvjitlink-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, + { name = "nvidia-cublas-cu12", version = "12.8.4.1", source = { registry = "https://pypi.org/simple" }, marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, + { name = "nvidia-cusparse-cu12", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, + { name = "nvidia-nvjitlink-cu12", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/85/48/9a13d2975803e8cf2777d5ed57b87a0b6ca2cc795f9a4f59796a910bfb80/nvidia_cusolver_cu12-11.7.3.90-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:4376c11ad263152bd50ea295c05370360776f8c3427b30991df774f9fb26c450", size = 267506905, upload-time = "2025-03-07T01:47:16.273Z" }, @@ -5732,7 +6065,7 @@ name = "nvidia-cusparse-cu12" version = "12.5.8.93" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-nvjitlink-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, + { name = "nvidia-nvjitlink-cu12", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/c2/f5/e1854cb2f2bcd4280c44736c93550cc300ff4b8c95ebe370d0aa7d2b473d/nvidia_cusparse_cu12-12.5.8.93-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:1ec05d76bbbd8b61b06a80e1eaf8cf4959c3d4ce8e711b65ebd0443bb0ebb13b", size = 288216466, upload-time = "2025-03-07T01:48:13.779Z" }, @@ -6247,7 +6580,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "typing-extensions", marker = "python_full_version < '3.11'" }, @@ -6270,14 +6604,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "typing-extensions", marker = "python_full_version >= '3.11' and python_full_version < '3.13'" }, @@ -6503,7 +6841,8 @@ source = { registry = "https://pypi.org/simple" } resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "(python_full_version < '3.11' and platform_machine != 'aarch64') or (python_full_version < '3.11' and sys_platform != 'linux')" }, @@ -6572,13 +6911,17 @@ resolution-markers = [ "python_full_version == '3.12.*' and sys_platform == 'darwin'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "(python_full_version >= '3.11' and platform_machine != 'aarch64') or (python_full_version >= '3.11' and sys_platform != 'linux')" }, @@ -6878,6 +7221,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" @@ -7381,6 +7737,20 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/3a/d8/a211b3f85e99a0daa2ddec96c949cac6824bd305b040571b82a03dd62636/pycodestyle-2.12.1-py2.py3-none-any.whl", hash = "sha256:46f0fb92069a7c28ab7bb558f05bfc0110dac69a0cd23c61ea0040283a9d78b3", size = 31284, upload-time = "2024-08-04T20:26:53.173Z" }, ] +[[package]] +name = "pycollada" +version = "0.9.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 = "python-dateutil" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/5a/8d/52a5364a17eb96129962cae8d3ee7658775e085ad0ba38388684ad5944e9/pycollada-0.9.3.tar.gz", hash = "sha256:c34d6dcf0fe2eba5896f71c96d37a1c0fe1a61f08440fa0cfcec3dc2895d3302", size = 110826, upload-time = "2026-01-24T15:45:23.625Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/07/86/f1f61b7a0701f9d1299e5293d083318019f91021a4d449f94d59dbe024e4/pycollada-0.9.3-py3-none-any.whl", hash = "sha256:636e6496f60987586db82455ea7bbd9ade775e8181c6590c83b698b6cd53a9f5", size = 129206, upload-time = "2026-01-24T15:45:22.182Z" }, +] + [[package]] name = "pycparser" version = "3.0" @@ -8497,7 +8867,7 @@ wheels = [ [[package]] name = "rerun-sdk" -version = "0.29.2" +version = "0.30.2" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "attrs" }, @@ -8508,10 +8878,10 @@ dependencies = [ { name = "typing-extensions" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/ad/d1/6b31d12e726732dced50806b1cb0b5fb55c478ee4ac23d68f50db888cf2c/rerun_sdk-0.29.2-cp310-abi3-macosx_11_0_arm64.whl", hash = "sha256:ead2b4bb93cac553c9b524442e49ba5f34c30ab9db2225e1ed2ce2ee235ea46b", size = 112371441, upload-time = "2026-02-12T19:31:07.296Z" }, - { url = "https://files.pythonhosted.org/packages/dc/81/9b3619b37c8a7492ccbe9ea172dedc5ffb66b83ded82b8f443c1958fe1c0/rerun_sdk-0.29.2-cp310-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:a97f5601cb50c14ec665525c0cf65056167de1306958a0526ff1e8d384320076", size = 120304992, upload-time = "2026-02-12T19:31:12.499Z" }, - { url = "https://files.pythonhosted.org/packages/63/43/2590293ce7985cbb88f9fdd67b90c36b954116f6c75639b378f098b3ff61/rerun_sdk-0.29.2-cp310-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:392a7f2c3db660716b660f4b164f9b73a076100378781a3a2551edf290d00c23", size = 125305451, upload-time = "2026-02-12T19:31:17.319Z" }, - { url = "https://files.pythonhosted.org/packages/bc/06/b73e04344f2220d48c0583270a54873bca3b93ab476cf09629941afac8e5/rerun_sdk-0.29.2-cp310-abi3-win_amd64.whl", hash = "sha256:a3ccfbac8df89519a075f9dc3499a9e715c653a19a17de00d39fd218a589e009", size = 108289765, upload-time = "2026-02-12T19:31:22.616Z" }, + { url = "https://files.pythonhosted.org/packages/79/37/0bd89c08fec35b3b23f0ca38eff0fd9960c67734643730b45210b407e35d/rerun_sdk-0.30.2-cp310-abi3-macosx_11_0_arm64.whl", hash = "sha256:8d952bf7ae2a1b1ee6064435cc14c82858771c2c2f1ec48b8164d69f6e4f0708", size = 114280633, upload-time = "2026-03-11T10:10:03.535Z" }, + { url = "https://files.pythonhosted.org/packages/88/1b/ffa0335499343894648fa92cd655978a65de0f2c6fc2ddca9fe6b6f9c242/rerun_sdk-0.30.2-cp310-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:f9bbe66ba4e9532c1a062d2d488ba09009c2231441fcfb013454832a9bd1bdfb", size = 122292152, upload-time = "2026-03-11T10:10:13.558Z" }, + { url = "https://files.pythonhosted.org/packages/c5/89/182ef62bff3d9f190dd2e024b28cf0513ac7a83bc15b979e052c46c41f64/rerun_sdk-0.30.2-cp310-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:f3480847f124894d1c9bcbbdb4182a4c64986bf9d0d669e10752f0738ecac359", size = 127332181, upload-time = "2026-03-11T10:10:21.713Z" }, + { url = "https://files.pythonhosted.org/packages/71/85/d04383cb508970ab8e9d9004e1f5959c5de8cba1efa47de20f9a94912dd2/rerun_sdk-0.30.2-cp310-abi3-win_amd64.whl", hash = "sha256:87bef55c6fccdcc9c3b6ff377a68f465ab872ffc1d16184abb62a382b63668a0", size = 110063998, upload-time = "2026-03-11T10:10:30.277Z" }, ] [[package]] @@ -8697,6 +9067,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" @@ -8757,7 +9143,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "joblib", marker = "python_full_version < '3.11'" }, @@ -8812,14 +9199,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "joblib", marker = "python_full_version >= '3.11'" }, @@ -8875,7 +9266,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, @@ -8942,14 +9334,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, @@ -9026,7 +9422,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "optype", version = "0.9.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, @@ -9049,14 +9446,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "optype", version = "0.16.0", source = { registry = "https://pypi.org/simple" }, extra = ["numpy"], marker = "python_full_version >= '3.11'" }, @@ -9097,6 +9498,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" @@ -9324,6 +9793,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" @@ -9399,7 +9877,8 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "ml-dtypes", marker = "python_full_version < '3.11'" }, @@ -9442,14 +9921,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "ml-dtypes", marker = "python_full_version >= '3.11'" }, @@ -9924,24 +10407,40 @@ 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" source = { registry = "https://pypi.org/simple" } wheels = [ - { url = "https://files.pythonhosted.org/packages/44/ba/b1b04f4b291a3205d95ebd24465de0e5bf010a2df27a4e58a9b5f039d8f2/triton-3.6.0-cp310-cp310-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:6c723cfb12f6842a0ae94ac307dba7e7a44741d720a40cf0e270ed4a4e3be781", size = 175972180, upload-time = "2026-01-20T16:15:53.664Z" }, { url = "https://files.pythonhosted.org/packages/8c/f7/f1c9d3424ab199ac53c2da567b859bcddbb9c9e7154805119f8bd95ec36f/triton-3.6.0-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a6550fae429e0667e397e5de64b332d1e5695b73650ee75a6146e2e902770bea", size = 188105201, upload-time = "2026-01-20T16:00:29.272Z" }, - { url = "https://files.pythonhosted.org/packages/0f/2c/96f92f3c60387e14cc45aed49487f3486f89ea27106c1b1376913c62abe4/triton-3.6.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:49df5ef37379c0c2b5c0012286f80174fcf0e073e5ade1ca9a86c36814553651", size = 176081190, upload-time = "2026-01-20T16:16:00.523Z" }, { url = "https://files.pythonhosted.org/packages/e0/12/b05ba554d2c623bffa59922b94b0775673de251f468a9609bc9e45de95e9/triton-3.6.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:e8e323d608e3a9bfcc2d9efcc90ceefb764a82b99dea12a86d643c72539ad5d3", size = 188214640, upload-time = "2026-01-20T16:00:35.869Z" }, - { url = "https://files.pythonhosted.org/packages/17/5d/08201db32823bdf77a0e2b9039540080b2e5c23a20706ddba942924ebcd6/triton-3.6.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:374f52c11a711fd062b4bfbb201fd9ac0a5febd28a96fb41b4a0f51dde3157f4", size = 176128243, upload-time = "2026-01-20T16:16:07.857Z" }, { url = "https://files.pythonhosted.org/packages/ab/a8/cdf8b3e4c98132f965f88c2313a4b493266832ad47fb52f23d14d4f86bb5/triton-3.6.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:74caf5e34b66d9f3a429af689c1c7128daba1d8208df60e81106b115c00d6fca", size = 188266850, upload-time = "2026-01-20T16:00:43.041Z" }, - { url = "https://files.pythonhosted.org/packages/3c/12/34d71b350e89a204c2c7777a9bba0dcf2f19a5bfdd70b57c4dbc5ffd7154/triton-3.6.0-cp313-cp313-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:448e02fe6dc898e9e5aa89cf0ee5c371e99df5aa5e8ad976a80b93334f3494fd", size = 176133521, upload-time = "2026-01-20T16:16:13.321Z" }, { url = "https://files.pythonhosted.org/packages/f9/0b/37d991d8c130ce81a8728ae3c25b6e60935838e9be1b58791f5997b24a54/triton-3.6.0-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:10c7f76c6e72d2ef08df639e3d0d30729112f47a56b0c81672edc05ee5116ac9", size = 188289450, upload-time = "2026-01-20T16:00:49.136Z" }, - { url = "https://files.pythonhosted.org/packages/ce/4e/41b0c8033b503fd3cfcd12392cdd256945026a91ff02452bef40ec34bee7/triton-3.6.0-cp313-cp313t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1722e172d34e32abc3eb7711d0025bb69d7959ebea84e3b7f7a341cd7ed694d6", size = 176276087, upload-time = "2026-01-20T16:16:18.989Z" }, { url = "https://files.pythonhosted.org/packages/35/f8/9c66bfc55361ec6d0e4040a0337fb5924ceb23de4648b8a81ae9d33b2b38/triton-3.6.0-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:d002e07d7180fd65e622134fbd980c9a3d4211fb85224b56a0a0efbd422ab72f", size = 188400296, upload-time = "2026-01-20T16:00:56.042Z" }, - { url = "https://files.pythonhosted.org/packages/49/55/5ecf0dcaa0f2fbbd4420f7ef227ee3cb172e91e5fede9d0ecaddc43363b4/triton-3.6.0-cp314-cp314-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ef5523241e7d1abca00f1d240949eebdd7c673b005edbbce0aca95b8191f1d43", size = 176138577, upload-time = "2026-01-20T16:16:25.426Z" }, { url = "https://files.pythonhosted.org/packages/df/3d/9e7eee57b37c80cec63322c0231bb6da3cfe535a91d7a4d64896fcb89357/triton-3.6.0-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a17a5d5985f0ac494ed8a8e54568f092f7057ef60e1b0fa09d3fd1512064e803", size = 188273063, upload-time = "2026-01-20T16:01:07.278Z" }, - { url = "https://files.pythonhosted.org/packages/48/db/56ee649cab5eaff4757541325aca81f52d02d4a7cd3506776cad2451e060/triton-3.6.0-cp314-cp314t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0b3a97e8ed304dfa9bd23bb41ca04cdf6b2e617d5e782a8653d616037a5d537d", size = 176274804, upload-time = "2026-01-20T16:16:31.528Z" }, { url = "https://files.pythonhosted.org/packages/f6/56/6113c23ff46c00aae423333eb58b3e60bdfe9179d542781955a5e1514cb3/triton-3.6.0-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:46bd1c1af4b6704e554cad2eeb3b0a6513a980d470ccfa63189737340c7746a7", size = 188397994, upload-time = "2026-01-20T16:01:14.236Z" }, ] @@ -10376,6 +10875,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" @@ -10474,6 +10995,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" @@ -10489,6 +11064,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" @@ -11023,6 +11621,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 35c5b28b52e79f698f686c893cf51b592537da7b Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 6 May 2026 22:05:14 +0200 Subject: [PATCH 02/23] feat(g1-wbc-sim): DIMOS_MUJOCO_VIEW=1 spawns native MuJoCo viewer in a separate process --- .../basic/unitree_g1_groot_wbc_sim.py | 44 ++++++ .../engines/mujoco_view_subprocess.py | 141 ++++++++++++++++++ 2 files changed, 185 insertions(+) create mode 100644 dimos/simulation/engines/mujoco_view_subprocess.py diff --git a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py index c340b004b4..5fae737b48 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py +++ b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py @@ -26,6 +26,9 @@ from __future__ import annotations +import os +import sys + from dimos.control.components import HardwareComponent, HardwareType from dimos.control.coordinator import ControlCoordinator, TaskConfig from dimos.core.coordination.blueprints import autoconnect @@ -45,8 +48,11 @@ ) from dimos.simulation.engines.mujoco_sim_module import MujocoSimModule from dimos.utils.data import get_data +from dimos.utils.logging_config import setup_logger from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule +logger = setup_logger() + _MJCF_PATH = "data/mujoco_sim/g1_gear_wbc.xml" _g1_engine = MujocoSimModule.blueprint( @@ -121,4 +127,42 @@ unitree_g1_groot_wbc_sim = autoconnect(_g1_engine, _g1_coordinator, _g1_ws_vis) + +# Optional native MuJoCo viewer in a separate process — read-only, mirrors +# the engine's joint state via LCM (no physics, no perf hit on the engine). +# Spawn from MainProcess only — worker imports of this module must be +# no-ops (workers are daemonic and can't spawn children). +import multiprocessing as _mp + +if ( + os.environ.get("DIMOS_MUJOCO_VIEW", "0") not in ("", "0") + and _mp.current_process().name == "MainProcess" +): + import shutil + import subprocess + + # mujoco.viewer.launch_passive needs ``mjpython`` on macOS; Linux + # runs fine under regular python. + if sys.platform == "darwin": + _viewer_python = shutil.which("mjpython") or shutil.which("python") + else: + _viewer_python = sys.executable + if _viewer_python is None: + logger.warning( + "DIMOS_MUJOCO_VIEW=1: couldn't locate mjpython/python on PATH; viewer not launched" + ) + else: + _viewer_proc = subprocess.Popen( + [ + _viewer_python, + "-m", + "dimos.simulation.engines.mujoco_view_subprocess", + _MJCF_PATH, + ], + ) + logger.info( + f"DIMOS_MUJOCO_VIEW=1: MuJoCo viewer subprocess started " + f"(pid={_viewer_proc.pid}, executable={_viewer_python}, mjcf={_MJCF_PATH})" + ) + __all__ = ["unitree_g1_groot_wbc_sim"] diff --git a/dimos/simulation/engines/mujoco_view_subprocess.py b/dimos/simulation/engines/mujoco_view_subprocess.py new file mode 100644 index 0000000000..82fbe3c7c6 --- /dev/null +++ b/dimos/simulation/engines/mujoco_view_subprocess.py @@ -0,0 +1,141 @@ +# 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 passive viewer subprocess for the in-process dimos sim. + +dimos's ``MujocoSimModule`` runs MuJoCo on a *worker* thread; on macOS +``mujoco.viewer.launch_passive`` requires the *main* thread (a glfw +constraint), which is why ``MujocoSimConfig.headless`` defaults to True +on Darwin. This module is a tiny standalone entry point that: + + 1. Loads the same MJCF dimos compiled. + 2. Subscribes to ``/coordinator/joint_state`` + ``/odom`` over LCM — + the topics the in-process engine already publishes. + 3. Mirrors that state into its own ``mujoco.MjData`` and renders via + ``mujoco.viewer.launch_passive`` from *its* main thread. + +It runs no physics — it's a viewer, not a second simulator — so what +you see is exactly the state the dimos engine is producing. + +Spawned by the GR00T sim blueprint when ``DIMOS_MUJOCO_VIEW=1``; the +blueprint uses ``multiprocessing.spawn`` so the subprocess gets a fresh +main thread regardless of how the dimos CLI was launched. +""" + +from __future__ import annotations + +import time +from typing import Any + +import numpy as np + + +def main(mjcf_path: str) -> None: + """Subprocess entry point. Blocks until the viewer window is closed.""" + import mujoco # type: ignore[import-untyped] + import mujoco.viewer as viewer # type: ignore[import-untyped] + + from dimos.core.transport import LCMTransport + from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped + from dimos.msgs.sensor_msgs.JointState import JointState + + # Inlined to avoid pulling in dimos.visualization.viser (the viser + # viewer is in a separate PR). Same definition as the version in + # robot_meshes.py: g1/left_hip_pitch -> left_hip_pitch_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" + + model = mujoco.MjModel.from_xml_path(mjcf_path) + data = mujoco.MjData(model) + mujoco.mj_forward(model, data) + + # Map joint name → qpos index (only hinge / slide joints have a + # 1-to-1 mapping with msg.position; the free joint at index 0 + # we update separately via /odom). + name_to_qposadr: dict[str, int] = {} + for jid in range(model.njnt): + name = mujoco.mj_id2name(model, mujoco.mjtObj.mjOBJ_JOINT, jid) + if not name: + continue + if model.jnt_type[jid] in (mujoco.mjtJoint.mjJNT_HINGE, mujoco.mjtJoint.mjJNT_SLIDE): + name_to_qposadr[name] = int(model.jnt_qposadr[jid]) + + # Latest state — written by LCM callbacks, read by the viewer loop. + latest: dict[str, Any] = {"joints": {}, "base_pos": None, "base_wxyz": None} + + def _on_joint_state(msg: JointState) -> None: + # Coordinator publishes dimos canonical names ("g1/left_hip_pitch") + # but the MJCF uses MuJoCo names ("left_hip_pitch_joint"); translate + # so the lookup against ``name_to_qposadr`` actually hits. + try: + for n, q in zip(list(msg.name), list(msg.position), strict=False): + latest["joints"][dimos_joint_to_mjcf(str(n))] = float(q) + except Exception: + pass + + def _on_odom(msg: PoseStamped) -> None: + try: + latest["base_pos"] = np.array( + [msg.position.x, msg.position.y, msg.position.z], dtype=np.float64 + ) + latest["base_wxyz"] = np.array( + [msg.orientation.w, msg.orientation.x, msg.orientation.y, msg.orientation.z], + dtype=np.float64, + ) + except Exception: + pass + + js_t: LCMTransport[JointState] = LCMTransport("/coordinator/joint_state", JointState) + js_t.start() + js_t.subscribe(_on_joint_state) + od_t: LCMTransport[PoseStamped] = LCMTransport("/odom", PoseStamped) + od_t.start() + od_t.subscribe(_on_odom) + + # The first qpos slots come from the free joint (px, py, pz, qw, qx, qy, qz). + # If the robot doesn't have one, fall back to leaving them alone. + has_freejoint = bool(model.njnt > 0 and model.jnt_type[0] == mujoco.mjtJoint.mjJNT_FREE) + free_qposadr = int(model.jnt_qposadr[0]) if has_freejoint else -1 + + # Use ``mj_kinematics`` (forward kinematics only) — we want to render + # whatever pose dimos is producing, not advance physics. + with viewer.launch_passive(model, data, show_left_ui=False, show_right_ui=True) as v: + while v.is_running(): + joints = dict(latest["joints"]) + base_pos = latest["base_pos"] + base_wxyz = latest["base_wxyz"] + for name, q in joints.items(): + adr = name_to_qposadr.get(name) + if adr is not None: + data.qpos[adr] = q + if has_freejoint and base_pos is not None and base_wxyz is not None: + data.qpos[free_qposadr : free_qposadr + 3] = base_pos + data.qpos[free_qposadr + 3 : free_qposadr + 7] = base_wxyz + mujoco.mj_kinematics(model, data) + v.sync() + time.sleep(1.0 / 60.0) + + js_t.stop() + od_t.stop() + + +if __name__ == "__main__": + import sys + + if len(sys.argv) != 2: + print("usage: python -m dimos.simulation.engines.mujoco_view_subprocess ") + sys.exit(2) + main(sys.argv[1]) From bf839132224fcee616f20d93d1296648b61d8c3b Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 6 May 2026 22:20:31 +0200 Subject: [PATCH 03/23] fix(g1-wbc-sim): inject menagerie mesh assets in MuJoCo viewer subprocess --- dimos/simulation/engines/mujoco_view_subprocess.py | 13 ++++++++++++- 1 file changed, 12 insertions(+), 1 deletion(-) diff --git a/dimos/simulation/engines/mujoco_view_subprocess.py b/dimos/simulation/engines/mujoco_view_subprocess.py index 82fbe3c7c6..673e58f0af 100644 --- a/dimos/simulation/engines/mujoco_view_subprocess.py +++ b/dimos/simulation/engines/mujoco_view_subprocess.py @@ -58,7 +58,18 @@ def dimos_joint_to_mjcf(name: str) -> str: suffix = parts[1] if len(parts) > 1 else parts[0] return f"{suffix}_joint" - model = mujoco.MjModel.from_xml_path(mjcf_path) + # G1 GR00T MJCF references meshes by bare filename (menagerie convention); + # from_xml_path can't find them on disk. Inject the dimos-bundled mesh + # bytes by name — same trick MujocoEngine uses. + try: + from dimos.simulation.mujoco.model import get_assets + + with open(mjcf_path) as _f: + _xml_str = _f.read() + model = mujoco.MjModel.from_xml_string(_xml_str, assets=get_assets()) + except Exception: + # Self-contained MJCFs (xarm scene.xml etc.) don't need assets. + model = mujoco.MjModel.from_xml_path(mjcf_path) data = mujoco.MjData(model) mujoco.mj_forward(model, data) From b7bb6c986992c9a3347e98f3ac29a76ab9fe95ab Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 6 May 2026 22:25:24 +0200 Subject: [PATCH 04/23] fix(g1-wbc-sim): tick_rate=50 + decimation=1 + ramp=0 to match GR00T training rate --- .../basic/unitree_g1_groot_wbc_sim.py | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py index 5fae737b48..af2a319542 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py +++ b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py @@ -70,7 +70,12 @@ ) _g1_coordinator = ControlCoordinator.blueprint( - tick_rate=500.0, + # 50 Hz coordinator tick — matches the rate the GR00T policy was + # trained at (decoupled_wbc/control/envs/g1/utils/joint_safety.py:38). + # Combined with the 200 Hz physics in g1_gear_wbc.xml gives a 4:1 + # sim/control ratio. Running faster (e.g. tick_rate=500) only burns + # CPU on duplicate inference. + tick_rate=50.0, publish_joint_state=True, joint_state_frame_id="coordinator", hardware=[ @@ -95,7 +100,15 @@ auto_start=True, auto_arm=True, auto_dry_run=False, - default_ramp_seconds=2.0, + # No ramp — policy commands torques the moment it arms, so + # the robot doesn't free-fall between MJCF spawn and policy + # takeover. Sim only; real hardware uses a non-zero ramp. + default_ramp_seconds=0.0, + # decimation=1 with tick_rate=50 → policy at 50 Hz (training + # rate). GrootWBCTaskConfig defaults to 10 (paired with the + # legacy 500 Hz tick); leaving the default with our 50 Hz + # tick yields 5 Hz policy and the robot tips over. + decimation=1, ), TaskConfig( name="servo_arms", From c3c0f823ff784a2228fcc12518eed9a7be564233 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 6 May 2026 22:29:27 +0200 Subject: [PATCH 05/23] fix(g1-wbc-sim): strip lidar/scene-mesh/multi-camera from mujoco_sim_module --- dimos/simulation/engines/mujoco_sim_module.py | 130 +----------------- 1 file changed, 5 insertions(+), 125 deletions(-) diff --git a/dimos/simulation/engines/mujoco_sim_module.py b/dimos/simulation/engines/mujoco_sim_module.py index cfe8476026..617a99fbd9 100644 --- a/dimos/simulation/engines/mujoco_sim_module.py +++ b/dimos/simulation/engines/mujoco_sim_module.py @@ -34,7 +34,6 @@ import mujoco import numpy as np -import open3d as o3d # type: ignore[import-untyped] from pydantic import Field import reactivex as rx from scipy.spatial.transform import Rotation as R @@ -107,20 +106,6 @@ class MujocoSimModuleConfig(ModuleConfig, DepthCameraConfig): enable_pointcloud: bool = False pointcloud_fps: float = 5.0 camera_info_fps: float = 1.0 - # Multi-camera lidar fusion. When non-empty, each camera in the - # list is rendered as a depth image, back-projected to world-frame - # points via depth_image_to_point_cloud(), and the union is - # voxel-downsampled before being published on `pointcloud`. This - # mirrors the legacy out-of-process mujoco_process.py behavior the - # Go2 sim has used since #862 — three 160°-FOV cameras stitched - # to a 360° scan so VoxelGridMapper's column-carving actually - # sees the same XY columns each frame and stops accumulating - # phantom obstacles behind a moving robot. When empty the - # original single-camera path runs unchanged. - 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 # Inject menagerie/dimos-bundled mesh bytes (via # dimos.simulation.mujoco.model.get_assets) into MjModel.from_xml_string. # MJCFs that reference meshes by bare filename (G1 GR00T, Go2) need this; @@ -237,13 +222,10 @@ def start(self) -> None: # steps — typically 5-30 ms per camera), so registering a camera # nobody consumes burns the 500 Hz tick deadline for nothing. # Skip the primary camera entirely when none of color / depth / - # pointcloud is enabled. Lidar cameras still register when - # `lidar_camera_names` is set. + # pointcloud is enabled. cameras: 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.config.enable_color or self.config.enable_depth or self.config.enable_pointcloud ) if primary_needed: cameras.append( @@ -254,35 +236,6 @@ def start(self) -> None: fps=float(self.config.fps), ) ) - # Self-occlusion filter for the lidar cameras: only render the - # static scene mesh (group 3) and the floor (group 2 — see - # comment in g1_gear_wbc.xml) — hide the robot's own collision - # (group 0) and visual (group 1) meshes. Without this the - # lidar back-projects the robot's hands / torso / arms from the - # 3 torso-mounted cameras' POVs into the global voxel map, - # leaving a robot-shaped halo of phantom obstacles that travels - # with the robot and blocks A* from finding any path out. - lidar_scene_option = mujoco.MjvOption() - # MjvOption.geomgroup is a 6-byte array; default is all visible. - lidar_scene_option.geomgroup[0] = 0 # robot collision meshes - lidar_scene_option.geomgroup[1] = 0 # robot visual meshes - lidar_scene_option.geomgroup[2] = 1 # floor (kept visible) - lidar_scene_option.geomgroup[3] = 1 # scene-mesh convex hulls - 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 # already registered as the RGBD camera - cameras.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, - ) - ) self._engine = MujocoEngine( config_path=Path(self.config.address), @@ -364,14 +317,8 @@ def start(self) -> None: ) ) - # Optional pointcloud generation. Two source modes: - # * Multi-camera lidar fusion (`lidar_camera_names` set) — each - # listed camera renders its own depth in the engine; we don't - # need `enable_depth` on the primary RGBD camera at all. - # * Single-camera fallback — back-projects the primary camera's - # depth image, so `enable_depth=True` IS required there. - _has_pointcloud_source = self.config.enable_depth or bool(self.config.lidar_camera_names) - if self.config.enable_pointcloud and _has_pointcloud_source: + # Optional pointcloud generation: back-projects primary camera depth. + if self.config.enable_pointcloud and self.config.enable_depth: pc_interval = 1.0 / self.config.pointcloud_fps self.register_disposable( rx.interval(pc_interval).subscribe( @@ -698,79 +645,12 @@ def _publish_tf(self, ts: float, cam_pos: np.ndarray, cam_mat: np.ndarray) -> No child_frame_id=self._camera_link, ts=ts, ), - # Alias for Detection3DModule's hardcoded "camera_optical" - # target frame (perception/detection/module3D.py:181). Same - # pose as color_optical; lets the lidar-driven object DB do - # tf.get("camera_optical", "world", ts) without code changes. - Transform( - translation=pos, - rotation=rot, - frame_id="world", - child_frame_id="camera_optical", - ts=ts, - ), ) def _generate_pointcloud(self) -> None: if self._engine is None: return - # Multi-camera lidar fusion: render every named lidar camera, - # back-project each depth image into world frame, concatenate, - # and voxel-downsample. The result is a single 360° point cloud - # with `frame_id="world"`, which is what VoxelGridMapper expects - # ("Assumes input clouds are already in world frame."). This - # matches the legacy mujoco_process.py behavior the Go2 sim has - # always used. - if self.config.lidar_camera_names: - try: - from dimos.simulation.mujoco.depth_camera import depth_image_to_point_cloud - - all_points: list[np.ndarray] = [] - latest_ts: float = 0.0 - for cam_name in self.config.lidar_camera_names: - frame = self._engine.read_camera(cam_name) - if frame is None: - continue - # ``mj_data.cam_xmat`` is stored flat; the helper wants - # a 3x3. Don't .copy() — the engine already gave us a - # snapshot, just view it as the right shape. - cam_mat3 = np.asarray(frame.cam_mat, dtype=np.float64).reshape(3, 3) - pts = depth_image_to_point_cloud( - frame.depth, - frame.cam_pos, - cam_mat3, - fov_degrees=frame.fovy, - ) - if pts.size > 0: - all_points.append(pts) - latest_ts = max(latest_ts, frame.timestamp) - if not all_points: - return - combined = np.vstack(all_points) - pcd_o3d = o3d.geometry.PointCloud() - pcd_o3d.points = o3d.utility.Vector3dVector(combined) - pcd_o3d = pcd_o3d.voxel_down_sample(self.config.lidar_voxel_size) - self.pointcloud.publish( - PointCloud2(pointcloud=pcd_o3d, ts=latest_ts or time.time(), frame_id="world") - ) - # Publish head-camera TF here so consumers (ObjectDBModule, - # MeshCameraModule's TF lookups, etc.) see the optical - # frame even when ``enable_color`` / ``enable_depth`` are - # off and the camera-publish loop never registers - # head_color as a renderer. Pose comes from MjData - # directly — populated every physics step regardless of - # rendering, so no GPU work added. - pose = self._engine.get_camera_pose(self.config.camera_name) - if pose is not None: - cam_pos, cam_mat = pose - self._publish_tf(latest_ts or time.time(), cam_pos, cam_mat) - except Exception as exc: - logger.error("Multi-camera lidar fusion error", error=str(exc)) - return - - # Single-camera fallback: produce a camera-frame pointcloud from - # the primary RGBD camera. Kept for manipulation-style sims that - # want a head-camera depth feed instead of a 360° lidar. + # Back-project the primary camera's depth image. if self._camera_info_base is None: return frame = self._engine.read_camera(self.config.camera_name) From a3ccd2c7d30b6608e7e20ad81ddda25c62e18541 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 6 May 2026 22:36:11 +0200 Subject: [PATCH 06/23] chore(g1-wbc): drop unused drive_trains/go2 + revert pyproject/uv.lock to dev (1500 LOC) --- .../drive_trains/unitree_g1/__init__.py | 19 - .../drive_trains/unitree_g1/adapter.py | 400 -------- .../drive_trains/unitree_go2/README.md | 69 -- .../drive_trains/unitree_go2/__init__.py | 19 - .../drive_trains/unitree_go2/adapter.py | 691 -------------- .../whole_body/unitree/go2/__init__.py | 15 - .../whole_body/unitree/go2/adapter.py | 254 ------ pyproject.toml | 43 +- uv.lock | 862 +++--------------- 9 files changed, 131 insertions(+), 2241 deletions(-) delete mode 100644 dimos/hardware/drive_trains/unitree_g1/__init__.py delete mode 100644 dimos/hardware/drive_trains/unitree_g1/adapter.py delete mode 100644 dimos/hardware/drive_trains/unitree_go2/README.md delete mode 100644 dimos/hardware/drive_trains/unitree_go2/__init__.py delete mode 100644 dimos/hardware/drive_trains/unitree_go2/adapter.py delete mode 100644 dimos/hardware/whole_body/unitree/go2/__init__.py delete mode 100644 dimos/hardware/whole_body/unitree/go2/adapter.py diff --git a/dimos/hardware/drive_trains/unitree_g1/__init__.py b/dimos/hardware/drive_trains/unitree_g1/__init__.py deleted file mode 100644 index 34c3e7dba4..0000000000 --- a/dimos/hardware/drive_trains/unitree_g1/__init__.py +++ /dev/null @@ -1,19 +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. - -"""Unitree G1 humanoid robot adapter.""" - -from dimos.hardware.drive_trains.unitree_g1.adapter import UnitreeG1TwistAdapter - -__all__ = ["UnitreeG1TwistAdapter"] diff --git a/dimos/hardware/drive_trains/unitree_g1/adapter.py b/dimos/hardware/drive_trains/unitree_g1/adapter.py deleted file mode 100644 index b5eb272f8a..0000000000 --- a/dimos/hardware/drive_trains/unitree_g1/adapter.py +++ /dev/null @@ -1,400 +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. - -"""Unitree G1 adapter — wraps Unitree SDK2 LocoClient for humanoid base control. - -The G1 is a humanoid robot with 3 DOF velocity control: [vx, vy, wz]. -This adapter uses the Unitree SDK2 Python bindings to communicate via DDS. - -G1 FSM states (discovered via testing): - FSM 0 = ZeroTorque - FSM 1 = Damp (robot collapses — NEVER call from adapter) - FSM 2 = Squat/Crouch - FSM 3 = Sit - FSM 4 = Lock Stand (rigid standing, no locomotion) - FSM 200 = Start (locomotion active, accepts Move commands) - FSM 702 = Lie2StandUp - FSM 706 = Squat2StandUp - -Initialization sequence: - 1. ChannelFactoryInitialize(0, interface) - Initialize DDS - 2. SetFsmId(4) - Lock stand (FSM 4) - 3. Start() - Activate locomotion (FSM 200) - 4. Move(vx, vy, vyaw) - Send velocity commands - -Shutdown: StopMove() only (robot stays standing). - -Note: Damp() and ZeroTorque() are NEVER called by the adapter — they -cause the robot to collapse and should only be invoked by the user. -""" - -from __future__ import annotations - -from dataclasses import dataclass -import threading -import time -from typing import TYPE_CHECKING - -from dimos.utils.logging_config import setup_logger - -if TYPE_CHECKING: - from unitree_sdk2py.core.channel import ChannelSubscriber # type: ignore[import-untyped] - from unitree_sdk2py.g1.loco.g1_loco_client import LocoClient # type: ignore[import-untyped] - from unitree_sdk2py.idl.unitree_go.msg.dds_ import ( # type: ignore[import-untyped] - SportModeState_, - ) - - from dimos.hardware.drive_trains.registry import TwistBaseAdapterRegistry - -logger = setup_logger() - - -@dataclass -class _Session: - """Active connection state for a G1.""" - - client: LocoClient - lock: threading.Lock - state_sub: ChannelSubscriber | None = None - latest_state: SportModeState_ | None = None - enabled: bool = False - locomotion_ready: bool = False - - -class UnitreeG1TwistAdapter: - """TwistBaseAdapter implementation for Unitree G1 humanoid. - - Communicates with G1 via Unitree SDK2 Python over DDS. - Expects 3 DOF: [vx, vy, wz] where: - - vx: forward/backward velocity (m/s) - - vy: left/right lateral velocity (m/s) - - wz: yaw rotation velocity (rad/s) - - Args: - dof: Number of velocity DOFs (must be 3 for G1) - network_interface: DDS network interface ID or name (default: 0) - """ - - def __init__( - self, - dof: int = 3, - network_interface: int | str | None = None, - address: str | None = None, - **_: object, - ) -> None: - if dof != 3: - raise ValueError(f"G1 only supports 3 DOF (vx, vy, wz), got {dof}") - - # Accept either network_interface= or address= (coordinator passes address=) - self._network_interface = network_interface or address or "eth0" - self._session: _Session | None = None - - def _get_session(self) -> _Session: - """Return active session or raise if not connected.""" - if self._session is None: - raise RuntimeError("G1 not connected") - return self._session - - # ========================================================================= - # Connection - # ========================================================================= - - def connect(self) -> bool: - """Connect to G1 via DDS and initialize the LocoClient.""" - try: - from unitree_sdk2py.core.channel import ChannelFactoryInitialize, ChannelSubscriber - from unitree_sdk2py.g1.loco.g1_loco_client import LocoClient - from unitree_sdk2py.idl.unitree_go.msg.dds_ import SportModeState_ - - # Initialize DDS - logger.info(f"Initializing DDS with network interface {self._network_interface}...") - ChannelFactoryInitialize(0, self._network_interface) - - # Create loco client - logger.info("Connecting to G1 LocoClient...") - client = LocoClient() - client.SetTimeout(10.0) - client.Init() - - # Create session — callback closes over it for state updates - session = _Session(client=client, lock=threading.Lock()) - - def state_callback(msg: SportModeState_) -> None: - with session.lock: - session.latest_state = msg - - state_sub = ChannelSubscriber("rt/sportmodestate", SportModeState_) - state_sub.Init(state_callback, 10) - session.state_sub = state_sub - - self._session = session - logger.info("Connected to G1") - - # Check if robot is freshly booted (FSM 0) — needs manual damp first - fsm = self._get_fsm_id() - if fsm == 0: - logger.warning( - "G1 is in FSM 0 (fresh boot). " - "Please put the robot in DAMP mode manually, then retry. " - "Waiting 10s for damp..." - ) - if not self._wait_for_fsm(1, timeout=30, settle=2): - logger.error("G1 did not enter damp mode (FSM 1). Cannot proceed.") - self.disconnect() - return False - - # Enter lock stand (FSM 4) so the robot is standing and ready - logger.info("Entering lock stand (FSM 4) on G1...") - session.client.SetFsmId(4) - if not self._wait_for_fsm(4): - logger.error("G1 failed to reach lock stand (FSM 4)") - self.disconnect() - return False - - return True - - except Exception as e: - logger.error(f"Failed to connect to G1: {e}") - self._session = None - return False - - def disconnect(self) -> None: - """Disconnect and safely shut down the robot. - - Stops motion but keeps the robot standing (in locomotion mode). - Does NOT call Damp/ZeroTorque/Squat — the user should manage - those transitions manually. - """ - session = self._session - if session is not None: - try: - logger.info("Stopping G1 motion...") - session.client.StopMove() - time.sleep(0.5) - except Exception as e: - logger.error(f"Error during disconnect: {e}") - - if session.state_sub is not None: - try: - session.state_sub.Close() - except Exception as e: - logger.error(f"Error closing state subscriber: {e}") - - self._session = None - - def is_connected(self) -> bool: - """Check if connected to G1.""" - return self._session is not None - - # ========================================================================= - # Info - # ========================================================================= - - def get_dof(self) -> int: - """G1 base is always 3 DOF (vx, vy, wz).""" - return 3 - - # ========================================================================= - # State Reading - # ========================================================================= - - def read_velocities(self) -> list[float]: - """Read actual velocities from SportModeState as [vx, vy, wz].""" - session = self._get_session() - with session.lock: - if session.latest_state is None: - return [0.0, 0.0, 0.0] - try: - state = session.latest_state - return [ - float(state.velocity[0]), # vx - float(state.velocity[1]), # vy - float(state.imu_state.gyroscope[2]), # wz (yaw rate) - ] - except Exception as e: - logger.warning(f"Error reading G1 velocities: {e}") - return [0.0, 0.0, 0.0] - - def read_odometry(self) -> list[float] | None: - """Read odometry from G1 as [x, y, theta]. - - Returns position from SportModeState which provides: - - position[0]: x (meters) - - position[1]: y (meters) - - imu_state.rpy[2]: yaw (radians) - """ - session = self._get_session() - with session.lock: - if session.latest_state is None: - return None - - try: - state = session.latest_state - return [ - float(state.position[0]), - float(state.position[1]), - float(state.imu_state.rpy[2]), # yaw - ] - except Exception as e: - logger.error(f"Error reading G1 odometry: {e}") - return None - - # ========================================================================= - # Control - # ========================================================================= - - def write_velocities(self, velocities: list[float]) -> bool: - """Send velocity command to G1. - - Args: - velocities: [vx, vy, wz] in standard frame (m/s, m/s, rad/s) - """ - if len(velocities) != 3: - return False - - session = self._get_session() - - if not session.enabled: - logger.warning("G1 not enabled, ignoring velocity command") - return False - - if not session.locomotion_ready: - logger.warning("G1 locomotion not ready, ignoring velocity command") - return False - - vx, vy, wz = velocities - return self._send_velocity(vx, vy, wz) - - def write_stop(self) -> bool: - """Stop all motion.""" - session = self._get_session() - try: - session.client.StopMove() - return True - except Exception as e: - logger.error(f"Error stopping G1: {e}") - return False - - # ========================================================================= - # Enable/Disable - # ========================================================================= - - def write_enable(self, enable: bool) -> bool: - """Enable/disable the platform. - - When enabling, ensures the robot is stood up and locomotion is ready. - When disabling, stops motion but keeps standing. - """ - session = self._get_session() - - if enable: - if not session.locomotion_ready: - logger.info("Starting G1 locomotion (FSM 200)...") - session.client.Start() - if not self._wait_for_fsm(200): - logger.error("G1 failed to reach locomotion mode (FSM 200)") - return False - session.locomotion_ready = True - - session.enabled = True - logger.info("G1 enabled") - return True - else: - self.write_stop() - session.enabled = False - logger.info("G1 disabled") - return True - - def read_enabled(self) -> bool: - """Check if platform is enabled.""" - return self._session is not None and self._session.enabled - - # ========================================================================= - # Internal - # ========================================================================= - - def _get_fsm_id(self) -> int | None: - """Query the current FSM ID from the robot. Returns None on failure.""" - import json - - from unitree_sdk2py.g1.loco.g1_loco_api import ( # type: ignore[import-untyped] - ROBOT_API_ID_LOCO_GET_FSM_ID, - ) - - session = self._get_session() - try: - # LocoClient has no public GetFsmId() — _Call is the standard RPC - # dispatch used by all SDK methods (SetFsmId, Move, etc.). - code, data = session.client._Call(ROBOT_API_ID_LOCO_GET_FSM_ID, "{}") - if code == 0 and data: - # data is like '{"data":4}' — parse as JSON for exact match - parsed = json.loads(str(data)) - return int(parsed["data"]) - except Exception as e: - logger.warning(f"Error querying FSM state: {e}") - return None - - def _wait_for_fsm(self, target_fsm: int, timeout: float = 10.0, settle: float = 5.0) -> bool: - """Poll GetFsmId until the robot reports the target FSM state. - - Args: - target_fsm: Expected FSM ID (e.g. 4 for lock stand, 200 for locomotion). - timeout: Maximum seconds to wait before giving up. - settle: Seconds to wait after reaching target state, letting the robot settle. - - Returns: - True if the target state was reached, False on timeout. - """ - deadline = time.time() + timeout - - while time.time() < deadline: - fsm = self._get_fsm_id() - if fsm == target_fsm: - logger.info(f"G1 reached FSM {target_fsm}, settling for {settle}s...") - time.sleep(settle) - return True - time.sleep(1) - - logger.error(f"Timed out waiting for G1 FSM {target_fsm}") - return False - - def _send_velocity(self, vx: float, vy: float, wz: float) -> bool: - """Send raw velocity to G1 via LocoClient.Move(). - - Uses default duration (1 second) since the coordinator tick loop - calls at 100Hz, providing continuous updates. - - Args: - vx: forward/backward velocity (m/s) - vy: left/right lateral velocity (m/s) - wz: yaw rotation velocity (rad/s) - """ - session = self._get_session() - try: - with session.lock: - session.client.Move(vx, vy, wz) - - return True - - except Exception as e: - logger.error(f"Error sending G1 velocity: {e}") - return False - - -def register(registry: TwistBaseAdapterRegistry) -> None: - """Register this adapter with the registry.""" - registry.register("unitree_g1", UnitreeG1TwistAdapter) - - -__all__ = ["UnitreeG1TwistAdapter"] diff --git a/dimos/hardware/drive_trains/unitree_go2/README.md b/dimos/hardware/drive_trains/unitree_go2/README.md deleted file mode 100644 index dea50cf728..0000000000 --- a/dimos/hardware/drive_trains/unitree_go2/README.md +++ /dev/null @@ -1,69 +0,0 @@ -# Unitree Go2 drive-train adapter - -[`adapter.py`](adapter.py) — `UnitreeGo2TwistAdapter` (high-level): Twist `(vx, vy, wz)` via SportClient, with optional Rage Mode (`rage_mode=True`, ~2.5 m/s forward envelope). Auto-registered as `"unitree_go2"` and used by blueprints like `unitree-go2-keyboard-teleop`. This is the one you want for teleop, navigation, or anything velocity-commanded. - ---- - -## Running - -Build the CycloneDDS C library via nix (once per machine — creates -`./result` symlink at the repo root, which acts as a GC root): - -```bash -nix build nixpkgs#cyclonedds -``` - -Point your shell / venv at it so `cyclonedds-python` can find the C -library at install and runtime. Easiest: append to `.venv/bin/activate` -so it's set every time you activate the venv: - -```bash -cat >> .venv/bin/activate < float: - return lo if x < lo else hi if x > hi else x - - -@dataclass -class _Session: - """Active connection state for a Go2. - - The session object is created by connect() and set on the adapter under - _session_lock. All mutable state that can be touched by both the DDS - callback thread and the control thread lives here, guarded by `lock`. - """ - - client: SportClient - motion_switcher: MotionSwitcherClient - lock: threading.Lock - state_sub: ChannelSubscriber | None = None - latest_state: SportModeState_ | None = None - enabled: bool = False - locomotion_ready: bool = False - - # Rage Mode joystick publisher (rt/wirelesscontroller_unprocessed path) - rage_active: bool = False - rage_pub: ChannelPublisher | None = None - rage_thread: threading.Thread | None = None - rage_stop: threading.Event | None = None - rage_cmd: tuple[float, float, float] = (0.0, 0.0, 0.0) - - -class UnitreeGo2TwistAdapter: - """TwistBaseAdapter for the Unitree Go2 quadruped via unitree_sdk2py (DDS). - - 3 DOF velocity: [vx, vy, wz]. - - vx: forward/backward linear velocity (m/s) - - vy: lateral (left positive) linear velocity (m/s) - - wz: yaw rate (rad/s) - - Thread model: - - _session_lock guards the self._session reference across threads. - - session.lock guards latest_state and SportClient RPC serialization. - Never take _session_lock while holding session.lock - the DDS callback - already holds session.lock briefly during state updates. - """ - - # AI-controller API ID for the Rage Mode toggle. - _SPORT_API_ID_RAGEMODE: int = 2059 - - # Rage velocity envelope (m/s, m/s, rad/s) from rage_mode_export_cfg.json. - _RAGE_UP_VX: float = 2.5 - _RAGE_UP_VY: float = 1.0 - _RAGE_UP_VYAW: float = 5.0 - - _RAGE_PUBLISH_HZ: float = 100.0 - _RAGE_LY_SIGN: float = 1.0 # vx → ly - _RAGE_LX_SIGN: float = -1.0 # vy → lx - _RAGE_RX_SIGN: float = -1.0 # wz → rx - - def __init__( - self, - dof: int = 3, - speed_level: int = 1, - rage_mode: bool = False, - **_: Any, - ) -> None: - if dof != 3: - raise ValueError(f"Go2 only supports 3 DOF (vx, vy, wz), got {dof}") - - self._session: _Session | None = None - self._session_lock = threading.Lock() - self._speed_level = speed_level - self._rage_mode_default = rage_mode - self._last_guard_warn_ts: float = 0.0 - - def connect(self) -> bool: - """Connect to Go2, verify sport mode, stand up, enter FreeWalk. - - Sequence: - 1. ChannelFactoryInitialize(0) — default domain, default NIC. - 2. MotionSwitcher.Init + poll CheckMode() until a sport mode - is reported (DDS discovery) or _DISCOVERY_TIMEOUT_S elapses. - 3. Subscribe rt/sportmodestate for telemetry. - 4. SportClient.Init. - 5. _initialize_locomotion(): StandUp + FreeWalk + SpeedLevel. - 6. If rage_mode=True, set_rage_mode(True). - - Returns True on success, False on connect/init/locomotion - failure. On failure, logs guidance and the adapter stays in a - clean "not connected" state so a retry can succeed. - """ - with self._session_lock: - if self._session is not None: - logger.warning("[Go2] Already connected — disconnect first") - return False - - # ChannelFactoryInitialize raises if the factory already exists. - try: - ChannelFactoryInitialize(0) - except Exception: - pass - - motion_switcher = MotionSwitcherClient() - motion_switcher.SetTimeout(0.5) - motion_switcher.Init() - - # Poll CheckMode() through DDS discovery - mode = "" - for _ in range(50): - try: - code, data = motion_switcher.CheckMode() - except (OSError, RuntimeError, TimeoutError): - time.sleep(0.1) - continue - if code == 0 and isinstance(data, dict): - mode = (data.get("name") or "").strip() - if mode: - break - time.sleep(0.1) - motion_switcher.SetTimeout(5.0) - if not mode: - logger.error("[Go2] No sport mode active") - return False - logger.info(f"[Go2] Sport mode '{mode}' active") - - client = SportClient() - client.SetTimeout(10.0) - - session = _Session( - client=client, - motion_switcher=motion_switcher, - lock=threading.Lock(), - ) - - def state_callback(msg: SportModeState_) -> None: - with session.lock: - session.latest_state = msg - - state_sub = ChannelSubscriber("rt/sportmodestate", SportModeState_) - state_sub.Init(state_callback, 10) - session.state_sub = state_sub - - with self._session_lock: - self._session = session - - # disconnect() must run on any failure - try: - client.Init() - logger.info("[Go2] Connected") - - if not self._initialize_locomotion(): - logger.error("[Go2] Failed to initialize locomotion mode") - self.disconnect() - return False - - if self._rage_mode_default and not self.set_rage_mode(True): - logger.warning("[Go2] Rage Mode enable failed — continuing with regular locomotion") - except Exception: - self.disconnect() - raise - - return True - - def disconnect(self) -> None: - """Stop motion, stand the robot down, and tear down DDS resources. - - Safe to call multiple times. Explicitly Close()s the state - subscriber to prevent DDS reader leaks across reconnects. - """ - with self._session_lock: - session = self._session - self._session = None - - if session is None: - return - - self._stop_rage_joystick(session) - try: - with session.lock: - session.client.StopMove() - with session.lock: - session.client.StandDown() - except (OSError, RuntimeError, TimeoutError) as e: - logger.error(f"[Go2] Error during disconnect: {e}") - - if session.state_sub is not None: - try: - session.state_sub.Close() - except (OSError, RuntimeError) as e: - logger.error(f"[Go2] Error closing state subscriber: {e}") - - def is_connected(self) -> bool: - with self._session_lock: - return self._session is not None - - def get_dof(self) -> int: - """Always 3 for Go2 (vx, vy, wz).""" - return 3 - - def read_velocities(self) -> list[float]: - """Measured velocities [vx, vy, wz] from SportModeState_. - - Sources: - vx, vy: state.velocity[0], state.velocity[1] - wz: state.imu_state.gyroscope[2] - - Returns [0.0, 0.0, 0.0] during the startup gap before the first - DDS callback has populated latest_state. - """ - session = self._get_session() - with session.lock: - if session.latest_state is None: - return [0.0, 0.0, 0.0] - state = session.latest_state - return [ - float(state.velocity[0]), - float(state.velocity[1]), - float(state.imu_state.gyroscope[2]), - ] - - def read_odometry(self) -> list[float] | None: - """Measured pose [x, y, theta] from SportModeState_. - - Sources: - x, y: state.position[0], state.position[1] - theta: state.imu_state.rpy[2] (yaw) - - Returns None if no state message has arrived yet. - """ - session = self._get_session() - with session.lock: - if session.latest_state is None: - return None - state = session.latest_state - return [ - float(state.position[0]), - float(state.position[1]), - float(state.imu_state.rpy[2]), - ] - - def write_velocities(self, velocities: list[float]) -> bool: - """Send a Twist command [vx, vy, wz] to the Go2. - - When Rage Mode is active, the command is stashed in - session.rage_cmd and the 100 Hz joystick publisher thread picks - it up on its next tick (Rage's FSM ignores SportClient.Move). - Otherwise the command is forwarded directly via - SportClient.Move() → FsmFreeWalk. - - Refuses (returns False) if: - - len(velocities) != 3 - - session not enabled (write_enable(True) not called) - - locomotion not ready (StandUp/FreeWalk incomplete) - - Guard warnings are rate-limited to 1 Hz since this is called - at 100 Hz from the tick loop. - """ - if len(velocities) != 3: - return False - - session = self._get_session() - - if not session.enabled: - self._warn_guard("Not enabled, ignoring velocity command") - return False - - if not session.locomotion_ready: - self._warn_guard("Locomotion not ready, ignoring velocity command") - return False - - vx, vy, wz = velocities - - if session.rage_active: - session.rage_cmd = (vx, vy, wz) - return True - - return self._send_velocity(vx, vy, wz) - - def _warn_guard(self, msg: str) -> None: - """Rate-limited guard warning (at most once per second). - - write_velocities runs at 100 Hz from the tick loop; without - throttling, a sustained guard miss would emit 100 warnings/s. - """ - now = time.monotonic() - if now - self._last_guard_warn_ts < 1.0: - return - self._last_guard_warn_ts = now - logger.warning(f"[Go2] {msg}") - - def write_stop(self) -> bool: - """Stop motion via SportClient.StopMove(). Leaves robot standing.""" - session = self._get_session() - with session.lock: - session.client.StopMove() - return True - - def write_enable(self, enable: bool) -> bool: - """Enable/disable velocity command path. - - enable=True: ensures locomotion is ready (re-initializes if needed), - then flips session.enabled. - enable=False: calls write_stop() and clears session.enabled. Does - NOT stand the robot down — use disconnect() for that. - """ - session = self._get_session() - - if enable: - if not session.locomotion_ready: - if not self._initialize_locomotion(): - logger.error("[Go2] Failed to initialize locomotion") - return False - session.enabled = True - logger.info("[Go2] Enabled") - return True - - self.write_stop() - session.enabled = False - logger.info("[Go2] Disabled") - return True - - def read_enabled(self) -> bool: - with self._session_lock: - return self._session is not None and self._session.enabled - - def check_mode(self) -> str | None: - """Return the current MotionSwitcher mode name, or None on RPC fail. - - Wraps MotionSwitcher.CheckMode(). Empty string means no controller - active; None means the RPC returned a non-zero code or non-dict data. - """ - session = self._get_session() - code, data = session.motion_switcher.CheckMode() - if code == 0 and isinstance(data, dict): - return (data.get("name") or "").strip() - return None - - def get_sport_state(self) -> SportModeState_ | None: - """Return the latest SportModeState_ snapshot for diagnostics. - - Returned object is the live SDK message — do not mutate it. None - if no state message has arrived. - """ - session = self._get_session() - with session.lock: - return session.latest_state - - def get_status(self) -> dict[str, Any]: - """One-shot snapshot of adapter + robot state""" - with self._session_lock: - session = self._session - - if session is None: - return { - "connected": False, - "mode": None, - "enabled": False, - "locomotion_ready": False, - "rage_active": False, - "speed_level": self._speed_level, - "has_state": False, - "velocity": None, - "position": None, - "body_height": None, - "sport_mode_num": None, - } - - mode = self.check_mode() - - with session.lock: - state = session.latest_state - enabled = session.enabled - locomotion_ready = session.locomotion_ready - rage_active = session.rage_active - - velocity: list[float] | None = None - position: list[float] | None = None - body_height: float | None = None - sport_mode_num: int | None = None - - if state is not None: - try: - velocity = [ - float(state.velocity[0]), - float(state.velocity[1]), - float(state.imu_state.gyroscope[2]), - ] - position = [ - float(state.position[0]), - float(state.position[1]), - float(state.imu_state.rpy[2]), - ] - body_height = float(state.body_height) - sport_mode_num = int(state.mode) - except (AttributeError, IndexError, TypeError, ValueError): - pass - - return { - "connected": True, - "mode": mode, - "enabled": enabled, - "locomotion_ready": locomotion_ready, - "rage_active": rage_active, - "speed_level": self._speed_level, - "has_state": state is not None, - "velocity": velocity, - "position": position, - "body_height": body_height, - "sport_mode_num": sport_mode_num, - } - - def set_speed_level(self, level: int) -> bool: - """Set the SportClient speed envelope at runtime. - - Go2 SDK convention: -1 = slow, 0 = normal, 1 = fast (max). When - Rage is active, the Rage envelope (_RAGE_UP_VX etc.) applies - instead. Updates self._speed_level so subsequent - _initialize_locomotion() calls apply the same level. - - Returns True if the RPC returned 0. - """ - session = self._get_session() - with session.lock: - ret = session.client.SpeedLevel(level) - - if ret != 0: - logger.warning(f"[Go2] SpeedLevel({level}) returned {ret}") - return False - - self._speed_level = level - logger.info(f"[Go2] SpeedLevel set to {level}") - return True - - def set_rage_mode(self, enable: bool) -> bool: - """Toggle Rage Mode (api_id 2059) — widens forward envelope to ~2.5 m/s. - - Velocity input flows via rt/wirelesscontroller_unprocessed, not - SportClient.Move (FsmRageMode isn't in AiController::Move's dispatch). - Idempotent. Returns True on 2059 success; publisher/SwitchJoystick - failures are logged but don't fail the call. - """ - session = self._get_session() - - if session.rage_active == enable: - return True - - with session.lock: - ret = session.client.BalanceStand() - if ret != 0: - # Non-zero is usually benign here (already balanced / FSM transition - # in progress) — only fatal if the rage toggle below also fails. - logger.info(f"[Go2] BalanceStand returned {ret} (likely already balanced — proceeding)") - time.sleep(0.3) - - if not self._call_sport_api(self._SPORT_API_ID_RAGEMODE, {"data": enable}): - return False - - if enable: - time.sleep(2.0) # let FsmRageMode transition settle - self._start_rage_joystick(session) - with session.lock: - sj_ret = session.client.SwitchJoystick(True) - if sj_ret != 0: - logger.warning(f"[Go2] SwitchJoystick(True) after rage returned {sj_ret}") - else: - self._stop_rage_joystick(session) - with session.lock: - sj_ret = session.client.SwitchJoystick(False) - if sj_ret != 0: - logger.warning(f"[Go2] SwitchJoystick(False) after rage returned {sj_ret}") - - logger.info(f"[Go2] Rage Mode {'enabled' if enable else 'disabled'}") - return True - - def _start_rage_joystick(self, session: _Session) -> None: - """Create the WirelessController publisher and spawn the 100Hz thread.""" - if session.rage_pub is not None: - return - pub = ChannelPublisher("rt/wirelesscontroller_unprocessed", WirelessController_) - pub.Init() - session.rage_pub = pub - - session.rage_stop = threading.Event() - session.rage_cmd = (0.0, 0.0, 0.0) - session.rage_active = True - session.rage_thread = threading.Thread( - target=self._rage_joystick_loop, - args=(session,), - name="go2-rage-joystick", - daemon=True, - ) - session.rage_thread.start() - - def _stop_rage_joystick(self, session: _Session) -> None: - """Stop the publisher thread and release the DDS writer. - - Closes ChannelPublisher explicitly to avoid leaking the DDS writer - across repeated set_rage_mode(True/False) cycles. - """ - session.rage_active = False - if session.rage_stop is not None: - session.rage_stop.set() - if session.rage_thread is not None: - session.rage_thread.join(timeout=1.0) - session.rage_thread = None - session.rage_stop = None - if session.rage_pub is not None: - try: - session.rage_pub.Close() - except (OSError, RuntimeError) as e: - logger.warning(f"[Go2] Rage publisher Close raised: {e}") - session.rage_pub = None - - def _rage_joystick_loop(self, session: _Session) -> None: - """Publish the latest rage_cmd as a WirelessController_ message. - - Runs at _RAGE_PUBLISH_HZ. On each tick, reads session.rage_cmd, - normalizes to stick axes via the envelope constants, and writes - a WirelessController_ message. Exits when rage_stop is set or - the session's publisher is torn down. - """ - period = 1.0 / self._RAGE_PUBLISH_HZ - msg = unitree_go_msg_dds__WirelessController_() - msg.keys = 0 - msg.ry = 0.0 - - while session.rage_stop is not None and not session.rage_stop.wait(period): - pub = session.rage_pub - if pub is None: - return - vx, vy, wz = session.rage_cmd - - ly = _clip(vx / self._RAGE_UP_VX, -1.0, 1.0) * self._RAGE_LY_SIGN - lx = _clip(vy / self._RAGE_UP_VY, -1.0, 1.0) * self._RAGE_LX_SIGN - rx = _clip(wz / self._RAGE_UP_VYAW, -1.0, 1.0) * self._RAGE_RX_SIGN - - msg.lx = float(lx) - msg.ly = float(ly) - msg.rx = float(rx) - - try: - pub.Write(msg) - except (OSError, RuntimeError) as e: - logger.warning(f"[Go2] Rage joystick publish raised: {e}") - return - - def _call_sport_api(self, api_id: int, payload: dict[str, Any] | None = None) -> bool: - """Generic escape hatch for undocumented mcf sport API IDs. - - SportClient's internal dispatcher rejects unregistered api_ids - with code 3103 (RPC_ERR_CLIENT_API_NOT_REG) before any message - leaves the process — the public SDK only registers its named - methods in __init__. We call _RegistApi() first (idempotent dict - set) so undocumented IDs like RAGEMODE reach the robot. - - Uses leading-underscore SDK methods (_RegistApi, _Call) — these - are not part of the public SDK contract. Verified working against - unitree-sdk2py-dimos>=1.0.2; retest if the SDK is upgraded. - - Returns True on RPC code 0. On failure, logs code + response. - """ - session = self._get_session() - body = json.dumps(payload or {}) - with session.lock: - session.client._RegistApi(api_id, 0) - code, data = session.client._Call(api_id, body) - - if code != 0: - logger.warning(f"[Go2] _Call({api_id}, {body}) -> code={code} data={data!r}") - return False - return True - - def _get_session(self) -> _Session: - """Return active session or raise RuntimeError if disconnected. - - Note: callers using the returned session.lock must NEVER then - try to acquire self._session_lock — see the lock-ordering rule - in the class docstring. - """ - session = self._session - if session is None: - raise RuntimeError("Go2 not connected") - return session - - def _initialize_locomotion(self) -> bool: - """StandUp → 3s settle → FreeWalk → 2s settle → SpeedLevel. - - Called from connect() and from write_enable(True) if locomotion - was not yet ready. Assumes a sport mode is already active. - """ - session = self._get_session() - - if not self.check_mode(): - logger.error("[Go2] No sport mode active") - return False - - logger.info("[Go2] Standing up...") - with session.lock: - ret = session.client.StandUp() - if ret != 0: - logger.error(f"[Go2] StandUp failed with code {ret}") - return False - time.sleep(3) - - logger.info("[Go2] Activating FreeWalk...") - with session.lock: - ret = session.client.FreeWalk() - if ret != 0: - logger.error(f"[Go2] FreeWalk failed with code {ret}") - return False - time.sleep(2) - - with session.lock: - sl_ret = session.client.SpeedLevel(self._speed_level) - if sl_ret == 0: - logger.info(f"[Go2] SpeedLevel({self._speed_level}) applied") - else: - logger.warning(f"[Go2] SpeedLevel({self._speed_level}) returned {sl_ret}") - - session.locomotion_ready = True - logger.info("[Go2] Locomotion ready") - return True - - def _send_velocity(self, vx: float, vy: float, wz: float) -> bool: - session = self._get_session() - with session.lock: - ret = session.client.Move(vx, vy, wz) - if ret != 0: - logger.warning(f"[Go2] Move() returned code {ret}") - return False - return True - - -def register(registry: TwistBaseAdapterRegistry) -> None: - registry.register("unitree_go2", UnitreeGo2TwistAdapter) - - -__all__ = ["UnitreeGo2TwistAdapter"] diff --git a/dimos/hardware/whole_body/unitree/go2/__init__.py b/dimos/hardware/whole_body/unitree/go2/__init__.py deleted file mode 100644 index 1582089168..0000000000 --- a/dimos/hardware/whole_body/unitree/go2/__init__.py +++ /dev/null @@ -1,15 +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. - -"""Unitree Go2 low-level quadruped adapter.""" diff --git a/dimos/hardware/whole_body/unitree/go2/adapter.py b/dimos/hardware/whole_body/unitree/go2/adapter.py deleted file mode 100644 index 6e6415964c..0000000000 --- a/dimos/hardware/whole_body/unitree/go2/adapter.py +++ /dev/null @@ -1,254 +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. - -"""Unitree Go2 low-level adapter — direct 12-DOF joint control over DDS. - -Uses ``rt/lowcmd`` / ``rt/lowstate`` DDS topics for 500 Hz motor-level -position/velocity/torque control, bypassing the high-level SportClient. - -Important: The Go2 must first exit sport mode (via MotionSwitcherClient) -before low-level commands are accepted. - -Motor ordering (12 leg joints): - 0-2: FR (hip, thigh, calf) - 3-5: FL - 6-8: RR - 9-11: RL -""" - -from __future__ import annotations - -import threading -import time -from typing import TYPE_CHECKING - -from dimos.hardware.whole_body.spec import ( - POS_STOP, - VEL_STOP, - IMUState, - MotorCommand, - MotorState, -) -from dimos.utils.logging_config import setup_logger - -if TYPE_CHECKING: - from dimos.hardware.whole_body.registry import WholeBodyAdapterRegistry - -logger = setup_logger() - -_NUM_MOTORS = 12 - - -class UnitreeGo2LowLevelAdapter: - """WholeBodyAdapter implementation for Unitree Go2 — low-level DDS. - - The coordinator's tick loop drives the publish cadence. Each call to - ``write_motor_commands()`` updates the ``LowCmd_`` buffer, computes - CRC, and publishes immediately — no background thread needed. - - Args: - network_interface: DDS network interface ID (default: 0). - """ - - def __init__(self, network_interface: int = 0, **_: object) -> None: - self._network_interface = network_interface - - self._connected = False - self._lock = threading.Lock() - - # SDK objects (lazy-imported on connect) - self._low_cmd = None - self._publisher = None - self._subscriber = None - self._crc = None - - # Latest feedback - self._low_state = None - - # ========================================================================= - # Connection - # ========================================================================= - - def connect(self) -> bool: - """Connect to Go2 and release sport mode for low-level control.""" - try: - from unitree_sdk2py.core.channel import ( - ChannelFactoryInitialize, - ChannelPublisher, - ChannelSubscriber, - ) - from unitree_sdk2py.idl.default import unitree_go_msg_dds__LowCmd_ - from unitree_sdk2py.idl.unitree_go.msg.dds_ import LowCmd_, LowState_ - from unitree_sdk2py.utils.crc import CRC - - # 1. Initialise DDS transport - logger.info(f"Initializing DDS (low-level) with interface {self._network_interface}...") - ChannelFactoryInitialize(self._network_interface) - - # 2. Create publisher / subscriber - self._publisher = ChannelPublisher("rt/lowcmd", LowCmd_) - self._publisher.Init() - - self._subscriber = ChannelSubscriber("rt/lowstate", LowState_) - self._subscriber.Init(self._on_low_state, 10) - - # 3. Initialise LowCmd with safe defaults - self._low_cmd = unitree_go_msg_dds__LowCmd_() - self._low_cmd.head[0] = 0xFE - self._low_cmd.head[1] = 0xEF - self._low_cmd.level_flag = 0xFF - self._low_cmd.gpio = 0 - for i in range(20): - self._low_cmd.motor_cmd[i].mode = 0x01 # PMSM mode - self._low_cmd.motor_cmd[i].q = POS_STOP - self._low_cmd.motor_cmd[i].kp = 0 - self._low_cmd.motor_cmd[i].dq = VEL_STOP - self._low_cmd.motor_cmd[i].kd = 0 - self._low_cmd.motor_cmd[i].tau = 0 - - self._crc = CRC() - - # 4. Release sport mode so low-level commands are accepted - logger.info("Releasing sport mode...") - self._release_sport_mode() - - self._connected = True - logger.info("Go2 low-level adapter connected") - return True - - except Exception as e: - logger.error(f"Failed to connect Go2 low-level adapter: {e}") - self._connected = False - return False - - def disconnect(self) -> None: - """Disconnect from the robot.""" - self._connected = False - self._publisher = None - self._subscriber = None - self._low_cmd = None - self._low_state = None - logger.info("Go2 low-level adapter disconnected") - - def is_connected(self) -> bool: - return self._connected - - # ========================================================================= - # State Reading - # ========================================================================= - - def read_motor_states(self) -> list[MotorState]: - """Read motor states for all 12 leg joints.""" - with self._lock: - if self._low_state is None: - return [MotorState()] * _NUM_MOTORS - return [ - MotorState( - q=self._low_state.motor_state[i].q, - dq=self._low_state.motor_state[i].dq, - tau=self._low_state.motor_state[i].tau_est, - ) - for i in range(_NUM_MOTORS) - ] - - def read_imu(self) -> IMUState: - """Read IMU state.""" - with self._lock: - if self._low_state is None: - return IMUState() - imu = self._low_state.imu_state - return IMUState( - quaternion=tuple(imu.quaternion), - gyroscope=tuple(imu.gyroscope), - accelerometer=tuple(imu.accelerometer), - rpy=tuple(imu.rpy), - ) - - def read_foot_forces(self) -> list[float]: - """Read foot force sensors (4 feet).""" - with self._lock: - if self._low_state is None: - return [0.0] * 4 - return [float(self._low_state.foot_force[i]) for i in range(4)] - - # ========================================================================= - # Control - # ========================================================================= - - def write_motor_commands(self, commands: list[MotorCommand]) -> bool: - """Update command buffer, compute CRC, and publish immediately. - - Called by the coordinator tick loop on every tick — no background - thread needed. - """ - if len(commands) != _NUM_MOTORS: - logger.error(f"Expected {_NUM_MOTORS} commands, got {len(commands)}") - return False - - with self._lock: - if self._low_cmd is None or self._crc is None or self._publisher is None: - return False - for i, cmd in enumerate(commands): - self._low_cmd.motor_cmd[i].q = cmd.q - self._low_cmd.motor_cmd[i].dq = cmd.dq - self._low_cmd.motor_cmd[i].kp = cmd.kp - self._low_cmd.motor_cmd[i].kd = cmd.kd - self._low_cmd.motor_cmd[i].tau = cmd.tau - self._low_cmd.crc = self._crc.Crc(self._low_cmd) - self._publisher.Write(self._low_cmd) - return True - - # ========================================================================= - # Internal - # ========================================================================= - - def _on_low_state(self, msg: object) -> None: - """DDS callback for rt/lowstate.""" - with self._lock: - self._low_state = msg - - def _release_sport_mode(self) -> None: - """Exit sport mode so that low-level commands are accepted. - - Loops StandDown + ReleaseMode until CheckMode returns empty. - """ - from unitree_sdk2py.comm.motion_switcher.motion_switcher_client import ( - MotionSwitcherClient, - ) - from unitree_sdk2py.go2.sport.sport_client import SportClient - - sc = SportClient() - sc.SetTimeout(5.0) - sc.Init() - - msc = MotionSwitcherClient() - msc.SetTimeout(5.0) - msc.Init() - - _status, result = msc.CheckMode() - while result["name"]: - sc.StandDown() - msc.ReleaseMode() - _status, result = msc.CheckMode() - time.sleep(1) - - logger.info("Sport mode released — low-level control active") - - -def register(registry: WholeBodyAdapterRegistry) -> None: - """Register this adapter with the whole-body registry.""" - registry.register("unitree_go2", UnitreeGo2LowLevelAdapter) - - -__all__ = ["UnitreeGo2LowLevelAdapter"] diff --git a/pyproject.toml b/pyproject.toml index c243502933..630b1e578c 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -54,7 +54,7 @@ dependencies = [ # Core "numpy>=1.26.4", "scipy>=1.15.1", - "pin>=3.3.0", # Pinocchio IK library + "pin>=3.3.0", # Pinocchio IK library "reactivex", "sortedcontainers==2.4.0", "pydantic", @@ -77,16 +77,12 @@ dependencies = [ "typer>=0.19.2,<1", "plotext==5.3.2", # Used for calculating the occupancy map. - "numba>=0.60.0", # First version supporting Python 3.12 + "numba>=0.60.0", # First version supporting Python 3.12 "llvmlite>=0.42.0", # Required by numba 0.60+ # TODO: rerun shouldn't be required but rn its in core (there is NO WAY to use dimos without rerun rn) # remove this once rerun is optional in core - # Pinned to 0.30.x so rerun-sdk and dimos-viewer (which is a fork of - # rerun's 0.30 series) speak the same gRPC wire format. Allowing - # rerun-sdk 0.31+ produces a port mismatch (SDK→9876 vs viewer→9877) - # that crashes RerunBridge at startup. - "rerun-sdk>=0.30,<0.31", - "dimos-viewer>=0.30.0a2,<0.31", + "rerun-sdk>=0.20.0", + "dimos-viewer>=0.30.0a2", "toolz>=1.1.0", "protobuf>=6.33.5,<7", "psutil>=7.0.0", @@ -157,8 +153,8 @@ misc = [ ] visualization = [ - "rerun-sdk>=0.30,<0.31", - "dimos-viewer>=0.30.0a4,<0.31", + "rerun-sdk>=0.20.0", + "dimos-viewer>=0.30.0a4", ] agents = [ @@ -200,7 +196,7 @@ perception = [ unitree = [ "dimos[base]", - "unitree-webrtc-connect-leshy>=2.0.7", + "unitree-webrtc-connect-leshy>=2.0.7" ] unitree-dds = [ @@ -301,28 +297,6 @@ sim = [ "mujoco>=3.3.4", "playground>=0.0.5", "pygame>=2.6.1", - # USD/USDZ scene-mesh loader (used by dimos.mapping.mesh_scene for - # MeshCameraModule + bake_scene_mjcf collision wrapping). - "usd-core>=24.0", -] - -# Viser browser viewer + Gaussian splat scene loader. Opt-in. -# Required by ViserRenderModule (browser viewer at :8082) and by the -# splat loader used by both the viewer and the splat camera renderer. -viz = [ - "viser>=1.0.26", - "plyfile>=1.1.3", -] - -# 3D Gaussian splat camera renderer (Linux+CUDA only). Opt-in. -# gsplat builds CUDA kernels via nvcc/ninja on first import; first-time -# install is slow. Required only by the SplatCameraModule that -# publishes splat-rendered camera images. Pulls in [viz] for the splat -# loader. -splat = [ - "dimos[viz]", - "gsplat>=1.5.0", - "gsplat>=1.5.0; platform_machine == 'x86_64' and sys_platform == 'linux'", ] # NOTE: jetson-jp6-cuda126 extra is disabled due to 404 errors from wheel URLs @@ -491,8 +465,6 @@ concurrency = ["multiprocessing", "thread"] show_missing = true skip_empty = true -[tool.uv.sources] - [tool.largefiles] max_size_kb = 50 ignore = [ @@ -501,5 +473,4 @@ ignore = [ "dimos/dashboard/dimos.rbl", "dimos/web/dimos_interface/themes.json", "dimos/manipulation/manipulation_module.py", - "dimos/manipulation/planning/world/drake_world.py", ] diff --git a/uv.lock b/uv.lock index 9a72f9ede0..6e94931740 100644 --- a/uv.lock +++ b/uv.lock @@ -1,5 +1,5 @@ version = 1 -revision = 3 +revision = 2 requires-python = ">=3.10" resolution-markers = [ "python_full_version >= '3.14' and sys_platform == 'darwin'", @@ -10,23 +10,18 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] [[package]] @@ -500,7 +495,7 @@ name = "build" version = "1.4.0" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "colorama", marker = "(os_name == 'nt' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (os_name == 'nt' and sys_platform != 'darwin' and sys_platform != 'linux')" }, + { name = "colorama", marker = "(os_name == 'nt' and platform_machine != 'aarch64' and sys_platform == 'linux') or (os_name == 'nt' and sys_platform != 'darwin' and sys_platform != 'linux')" }, { name = "importlib-metadata", marker = "python_full_version < '3.10.2'" }, { name = "packaging" }, { name = "pyproject-hooks" }, @@ -755,8 +750,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "absl-py", marker = "python_full_version < '3.11'" }, @@ -784,18 +778,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "absl-py", marker = "python_full_version >= '3.11'" }, @@ -1176,8 +1166,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, @@ -1255,18 +1244,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, @@ -1545,7 +1530,7 @@ name = "cuda-bindings" version = "12.9.4" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "cuda-pathfinder", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, + { name = "cuda-pathfinder", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/7a/d8/b546104b8da3f562c1ff8ab36d130c8fe1dd6a045ced80b4f6ad74f7d4e1/cuda_bindings-12.9.4-cp310-cp310-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:4d3c842c2a4303b2a580fe955018e31aea30278be19795ae05226235268032e5", size = 12148218, upload-time = "2025-10-21T14:51:28.855Z" }, @@ -1912,12 +1897,6 @@ sim = [ { name = "mujoco" }, { name = "playground" }, { name = "pygame" }, - { name = "usd-core" }, -] -splat = [ - { name = "gsplat" }, - { name = "plyfile" }, - { name = "viser" }, ] unitree = [ { name = "anthropic" }, @@ -1987,10 +1966,6 @@ visualization = [ { name = "dimos-viewer" }, { name = "rerun-sdk" }, ] -viz = [ - { name = "plyfile" }, - { name = "viser" }, -] web = [ { name = "fastapi" }, { name = "ffmpeg-python" }, @@ -2016,11 +1991,10 @@ requires-dist = [ { name = "dimos", extras = ["agents", "web", "perception", "visualization"], marker = "extra == 'base'" }, { name = "dimos", extras = ["base"], marker = "extra == 'unitree'" }, { name = "dimos", extras = ["unitree"], marker = "extra == 'unitree-dds'" }, - { name = "dimos", extras = ["viz"], marker = "extra == 'splat'" }, { name = "dimos-lcm" }, { name = "dimos-lcm", marker = "extra == 'docker'" }, - { name = "dimos-viewer", specifier = ">=0.30.0a2,<0.31" }, - { name = "dimos-viewer", marker = "extra == 'visualization'", specifier = ">=0.30.0a4,<0.31" }, + { name = "dimos-viewer", specifier = ">=0.30.0a2" }, + { name = "dimos-viewer", marker = "extra == 'visualization'", specifier = ">=0.30.0a4" }, { name = "drake", marker = "platform_machine != 'aarch64' and sys_platform == 'darwin' and extra == 'manipulation'", specifier = "==1.45.0" }, { name = "drake", marker = "platform_machine != 'aarch64' and sys_platform != 'darwin' and extra == 'manipulation'", specifier = ">=1.40.0" }, { name = "edgetam-dimos", marker = "extra == 'misc'" }, @@ -2031,8 +2005,6 @@ requires-dist = [ { name = "filterpy", marker = "extra == 'perception'", specifier = ">=1.4.5" }, { name = "gdown", marker = "extra == 'misc'", specifier = "==5.2.0" }, { name = "googlemaps", marker = "extra == 'misc'", specifier = ">=4.10.0" }, - { name = "gsplat", marker = "platform_machine == 'x86_64' and sys_platform == 'linux' and extra == 'splat'", specifier = ">=1.5.0" }, - { name = "gsplat", marker = "extra == 'splat'", specifier = ">=1.5.0" }, { name = "hydra-core", marker = "extra == 'perception'", specifier = ">=1.3.0" }, { name = "ipykernel", marker = "extra == 'misc'" }, { name = "kaleido", marker = "extra == 'manipulation'", specifier = ">=0.2.1" }, @@ -2083,7 +2055,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" }, @@ -2113,9 +2084,9 @@ requires-dist = [ { name = "reactivex", marker = "extra == 'docker'" }, { name = "requests", marker = "extra == 'docker'", specifier = ">=2.28" }, { name = "requests-mock", marker = "extra == 'dev'", specifier = "==1.12.1" }, - { name = "rerun-sdk", specifier = ">=0.30,<0.31" }, + { name = "rerun-sdk", specifier = ">=0.20.0" }, { name = "rerun-sdk", marker = "extra == 'docker'" }, - { name = "rerun-sdk", marker = "extra == 'visualization'", specifier = ">=0.30,<0.31" }, + { name = "rerun-sdk", marker = "extra == 'visualization'", specifier = ">=0.20.0" }, { name = "rpyc", specifier = ">=6.0.0" }, { name = "ruff", marker = "extra == 'dev'", specifier = "==0.14.3" }, { name = "scikit-learn", marker = "extra == 'misc'" }, @@ -2166,9 +2137,7 @@ 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" }, @@ -2176,7 +2145,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", "splat", "drone", "dds", "docker", "base"] +provides-extras = ["misc", "visualization", "agents", "web", "perception", "unitree", "unitree-dds", "manipulation", "cpu", "cuda", "dev", "psql", "sim", "drone", "dds", "docker", "base"] [[package]] name = "dimos-lcm" @@ -2298,19 +2267,14 @@ source = { registry = "https://pypi.org/simple" } resolution-markers = [ "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "matplotlib", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux')" }, @@ -2410,35 +2374,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 != 'aarch64') or (python_full_version < '3.11' and sys_platform != 'linux')" }, - { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "(python_full_version >= '3.11' and platform_machine != 'aarch64') or (python_full_version >= '3.11' and sys_platform != 'linux')" }, -] -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" @@ -2759,8 +2694,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "jax", version = "0.6.2", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, @@ -2791,18 +2725,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "jax", version = "0.9.0.1", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, @@ -3085,23 +3015,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/48/b2/b096ccce418882fbfda4f7496f9357aaa9a5af1896a9a7f60d9f2b275a06/grpcio-1.78.0-cp314-cp314-win_amd64.whl", hash = "sha256:dce09d6116df20a96acfdbf85e4866258c3758180e8c49845d6ba8248b6d0bbb", size = 4929852, upload-time = "2026-02-06T09:56:45.885Z" }, ] -[[package]] -name = "gsplat" -version = "1.5.3" -source = { registry = "https://pypi.org/simple" } -dependencies = [ - { name = "jaxtyping" }, - { name = "ninja" }, - { 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 = "rich" }, - { name = "torch" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/6d/94/a0963873708223385ac926112dc3e40ab08297784ac53d95309b4cb5a801/gsplat-1.5.3.tar.gz", hash = "sha256:343f080c470e891ba3c697c03bdf0952cb982d1d535fdc24adb23c2cb4fba906", size = 4743603, upload-time = "2025-07-04T16:50:42.899Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/aa/68/c5cbbdb86421a3f45ac0b52cf9860b1048d089335151d3f37c23aabcbef1/gsplat-1.5.3-py3-none-any.whl", hash = "sha256:515a3773641f5e7f7717acab6276c0b1d6dbcad087b7968ca653337c3189a982", size = 6519041, upload-time = "2025-07-04T16:50:40.559Z" }, -] - [[package]] name = "h11" version = "0.16.0" @@ -3316,20 +3229,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" @@ -3404,8 +3303,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "colorama", marker = "python_full_version < '3.11' and sys_platform == 'win32'" }, @@ -3438,18 +3336,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "colorama", marker = "python_full_version >= '3.11' and sys_platform == 'win32'" }, @@ -3507,8 +3401,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "jaxlib", version = "0.6.2", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, @@ -3535,18 +3428,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "jaxlib", version = "0.9.0.1", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, @@ -3568,8 +3457,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "ml-dtypes", marker = "python_full_version < '3.11'" }, @@ -3610,18 +3498,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "ml-dtypes", marker = "python_full_version >= '3.11'" }, @@ -3677,7 +3561,7 @@ name = "jaxtyping" version = "0.3.7" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "wadler-lindig" }, + { name = "wadler-lindig", marker = "python_full_version >= '3.11'" }, ] sdist = { url = "https://files.pythonhosted.org/packages/38/40/a2ea3ce0e3e5f540eb970de7792c90fa58fef1b27d34c83f9fa94fea4729/jaxtyping-0.3.7.tar.gz", hash = "sha256:3bd7d9beb7d3cb01a89f93f90581c6f4fff3e5c5dc3c9307e8f8687a040d10c4", size = 45721, upload-time = "2026-01-30T14:18:47.409Z" } wheels = [ @@ -4706,118 +4590,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" @@ -5305,19 +5077,14 @@ source = { registry = "https://pypi.org/simple" } resolution-markers = [ "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux')" }, @@ -5399,62 +5166,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" @@ -5608,8 +5319,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] sdist = { url = "https://files.pythonhosted.org/packages/fd/1d/06475e1cd5264c0b870ea2cc6fdb3e37177c1e565c43f56ff17a10e3937f/networkx-3.4.2.tar.gz", hash = "sha256:307c3669428c5362aab27c8a1260aa8f47c4e91d3891f48be0141738d8d053e1", size = 2151368, upload-time = "2024-10-21T12:39:38.695Z" } wheels = [ @@ -5629,50 +5339,20 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] sdist = { url = "https://files.pythonhosted.org/packages/6a/51/63fe664f3908c97be9d2e4f1158eb633317598cfa6e1fc14af5383f17512/networkx-3.6.1.tar.gz", hash = "sha256:26b7c357accc0c8cde558ad486283728b65b6a95d85ee1cd66bafab4c8168509", size = 2517025, upload-time = "2025-12-08T17:02:39.908Z" } wheels = [ { url = "https://files.pythonhosted.org/packages/9e/c9/b2622292ea83fbb4ec318f5b9ab867d0a28ab43c5717bb85b0a5f6b3b0a4/networkx-3.6.1-py3-none-any.whl", hash = "sha256:d47fbf302e7d9cbbb9e2555a0d267983d2aa476bac30e90dfbe5669bd57f3762", size = 2068504, upload-time = "2025-12-08T17:02:38.159Z" }, ] -[[package]] -name = "ninja" -version = "1.13.0" -source = { registry = "https://pypi.org/simple" } -sdist = { url = "https://files.pythonhosted.org/packages/43/73/79a0b22fc731989c708068427579e840a6cf4e937fe7ae5c5d0b7356ac22/ninja-1.13.0.tar.gz", hash = "sha256:4a40ce995ded54d9dc24f8ea37ff3bf62ad192b547f6c7126e7e25045e76f978", size = 242558, upload-time = "2025-08-11T15:10:19.421Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/3c/74/d02409ed2aa865e051b7edda22ad416a39d81a84980f544f8de717cab133/ninja-1.13.0-py3-none-macosx_10_9_universal2.whl", hash = "sha256:fa2a8bfc62e31b08f83127d1613d10821775a0eb334197154c4d6067b7068ff1", size = 310125, upload-time = "2025-08-11T15:09:50.971Z" }, - { url = "https://files.pythonhosted.org/packages/8e/de/6e1cd6b84b412ac1ef327b76f0641aeb5dcc01e9d3f9eee0286d0c34fd93/ninja-1.13.0-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:3d00c692fb717fd511abeb44b8c5d00340c36938c12d6538ba989fe764e79630", size = 177467, upload-time = "2025-08-11T15:09:52.767Z" }, - { url = "https://files.pythonhosted.org/packages/c8/83/49320fb6e58ae3c079381e333575fdbcf1cca3506ee160a2dcce775046fa/ninja-1.13.0-py3-none-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:be7f478ff9f96a128b599a964fc60a6a87b9fa332ee1bd44fa243ac88d50291c", size = 187834, upload-time = "2025-08-11T15:09:54.115Z" }, - { url = "https://files.pythonhosted.org/packages/56/c7/ba22748fb59f7f896b609cd3e568d28a0a367a6d953c24c461fe04fc4433/ninja-1.13.0-py3-none-manylinux2014_ppc64le.manylinux_2_17_ppc64le.whl", hash = "sha256:60056592cf495e9a6a4bea3cd178903056ecb0943e4de45a2ea825edb6dc8d3e", size = 202736, upload-time = "2025-08-11T15:09:55.745Z" }, - { url = "https://files.pythonhosted.org/packages/79/22/d1de07632b78ac8e6b785f41fa9aad7a978ec8c0a1bf15772def36d77aac/ninja-1.13.0-py3-none-manylinux2014_s390x.manylinux_2_17_s390x.whl", hash = "sha256:1c97223cdda0417f414bf864cfb73b72d8777e57ebb279c5f6de368de0062988", size = 179034, upload-time = "2025-08-11T15:09:57.394Z" }, - { url = "https://files.pythonhosted.org/packages/ed/de/0e6edf44d6a04dabd0318a519125ed0415ce437ad5a1ec9b9be03d9048cf/ninja-1.13.0-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:fb46acf6b93b8dd0322adc3a4945452a4e774b75b91293bafcc7b7f8e6517dfa", size = 180716, upload-time = "2025-08-11T15:09:58.696Z" }, - { url = "https://files.pythonhosted.org/packages/54/28/938b562f9057aaa4d6bfbeaa05e81899a47aebb3ba6751e36c027a7f5ff7/ninja-1.13.0-py3-none-manylinux_2_28_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:4be9c1b082d244b1ad7ef41eb8ab088aae8c109a9f3f0b3e56a252d3e00f42c1", size = 146843, upload-time = "2025-08-11T15:10:00.046Z" }, - { url = "https://files.pythonhosted.org/packages/2a/fb/d06a3838de4f8ab866e44ee52a797b5491df823901c54943b2adb0389fbb/ninja-1.13.0-py3-none-manylinux_2_31_riscv64.whl", hash = "sha256:6739d3352073341ad284246f81339a384eec091d9851a886dfa5b00a6d48b3e2", size = 154402, upload-time = "2025-08-11T15:10:01.657Z" }, - { url = "https://files.pythonhosted.org/packages/31/bf/0d7808af695ceddc763cf251b84a9892cd7f51622dc8b4c89d5012779f06/ninja-1.13.0-py3-none-musllinux_1_2_aarch64.whl", hash = "sha256:11be2d22027bde06f14c343f01d31446747dbb51e72d00decca2eb99be911e2f", size = 552388, upload-time = "2025-08-11T15:10:03.349Z" }, - { url = "https://files.pythonhosted.org/packages/9d/70/c99d0c2c809f992752453cce312848abb3b1607e56d4cd1b6cded317351a/ninja-1.13.0-py3-none-musllinux_1_2_armv7l.whl", hash = "sha256:aa45b4037b313c2f698bc13306239b8b93b4680eb47e287773156ac9e9304714", size = 472501, upload-time = "2025-08-11T15:10:04.735Z" }, - { url = "https://files.pythonhosted.org/packages/9f/43/c217b1153f0e499652f5e0766da8523ce3480f0a951039c7af115e224d55/ninja-1.13.0-py3-none-musllinux_1_2_i686.whl", hash = "sha256:5f8e1e8a1a30835eeb51db05cf5a67151ad37542f5a4af2a438e9490915e5b72", size = 638280, upload-time = "2025-08-11T15:10:06.512Z" }, - { url = "https://files.pythonhosted.org/packages/8c/45/9151bba2c8d0ae2b6260f71696330590de5850e5574b7b5694dce6023e20/ninja-1.13.0-py3-none-musllinux_1_2_ppc64le.whl", hash = "sha256:3d7d7779d12cb20c6d054c61b702139fd23a7a964ec8f2c823f1ab1b084150db", size = 642420, upload-time = "2025-08-11T15:10:08.35Z" }, - { url = "https://files.pythonhosted.org/packages/3c/fb/95752eb635bb8ad27d101d71bef15bc63049de23f299e312878fc21cb2da/ninja-1.13.0-py3-none-musllinux_1_2_riscv64.whl", hash = "sha256:d741a5e6754e0bda767e3274a0f0deeef4807f1fec6c0d7921a0244018926ae5", size = 585106, upload-time = "2025-08-11T15:10:09.818Z" }, - { url = "https://files.pythonhosted.org/packages/c1/31/aa56a1a286703800c0cbe39fb4e82811c277772dc8cd084f442dd8e2938a/ninja-1.13.0-py3-none-musllinux_1_2_s390x.whl", hash = "sha256:e8bad11f8a00b64137e9b315b137d8bb6cbf3086fbdc43bf1f90fd33324d2e96", size = 707138, upload-time = "2025-08-11T15:10:11.366Z" }, - { url = "https://files.pythonhosted.org/packages/34/6f/5f5a54a1041af945130abdb2b8529cbef0cdcbbf9bcf3f4195378319d29a/ninja-1.13.0-py3-none-musllinux_1_2_x86_64.whl", hash = "sha256:b4f2a072db3c0f944c32793e91532d8948d20d9ab83da9c0c7c15b5768072200", size = 581758, upload-time = "2025-08-11T15:10:13.295Z" }, - { url = "https://files.pythonhosted.org/packages/95/97/51359c77527d45943fe7a94d00a3843b81162e6c4244b3579fe8fc54cb9c/ninja-1.13.0-py3-none-win32.whl", hash = "sha256:8cfbb80b4a53456ae8a39f90ae3d7a2129f45ea164f43fadfa15dc38c4aef1c9", size = 267201, upload-time = "2025-08-11T15:10:15.158Z" }, - { url = "https://files.pythonhosted.org/packages/29/45/c0adfbfb0b5895aa18cec400c535b4f7ff3e52536e0403602fc1a23f7de9/ninja-1.13.0-py3-none-win_amd64.whl", hash = "sha256:fb8ee8719f8af47fed145cced4a85f0755dd55d45b2bddaf7431fa89803c5f3e", size = 309975, upload-time = "2025-08-11T15:10:16.697Z" }, - { url = "https://files.pythonhosted.org/packages/df/93/a7b983643d1253bb223234b5b226e69de6cda02b76cdca7770f684b795f5/ninja-1.13.0-py3-none-win_arm64.whl", hash = "sha256:3c0b40b1f0bba764644385319028650087b4c1b18cdfa6f45cb39a3669b81aa9", size = 290806, upload-time = "2025-08-11T15:10:18.018Z" }, -] - [[package]] name = "nodeenv" version = "1.10.0" @@ -5723,8 +5403,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] sdist = { url = "https://files.pythonhosted.org/packages/76/21/7d2a95e4bba9dc13d043ee156a356c0a8f0c6309dff6b21b4d71a073b8a8/numpy-2.2.6.tar.gz", hash = "sha256:e29554e2bef54a90aa5cc07da6ce955accb83f21ab5de01a62c8478897b264fd", size = 20276440, upload-time = "2025-05-17T22:38:04.611Z" } wheels = [ @@ -5797,18 +5476,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] sdist = { url = "https://files.pythonhosted.org/packages/76/65/21b3bc86aac7b8f2862db1e808f1ea22b028e30a225a34a5ede9bf8678f2/numpy-2.3.5.tar.gz", hash = "sha256:784db1dcdab56bf0517743e746dfb0f885fc68d948aba86eeec2cba234bdf1c0", size = 20584950, upload-time = "2025-11-16T22:52:42.067Z" } wheels = [ @@ -5904,16 +5579,11 @@ name = "nvidia-cublas-cu12" version = "12.8.4.1" source = { registry = "https://pypi.org/simple" } resolution-markers = [ - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] wheels = [ { url = "https://files.pythonhosted.org/packages/29/99/db44d685f0e257ff0e213ade1964fc459b4a690a73293220e98feb3307cf/nvidia_cublas_cu12-12.8.4.1-py3-none-manylinux_2_27_aarch64.whl", hash = "sha256:b86f6dd8935884615a0683b663891d43781b819ac4f2ba2b0c9604676af346d0", size = 590537124, upload-time = "2025-03-07T01:43:53.556Z" }, @@ -5943,6 +5613,7 @@ resolution-markers = [ ] wheels = [ { url = "https://files.pythonhosted.org/packages/82/6c/90d3f532f608a03a13c1d6c16c266ffa3828e8011b1549d3b61db2ad59f5/nvidia_cublas_cu12-12.9.1.4-py3-none-manylinux_2_27_aarch64.whl", hash = "sha256:7a950dae01add3b415a5a5cdc4ec818fb5858263e9cca59004bb99fdbbd3a5d6", size = 575006342, upload-time = "2025-06-05T20:04:16.902Z" }, + { url = "https://files.pythonhosted.org/packages/77/3c/aa88abe01f3be3d1f8f787d1d33dc83e76fec05945f9a28fbb41cfb99cd5/nvidia_cublas_cu12-12.9.1.4-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:453611eb21a7c1f2c2156ed9f3a45b691deda0440ec550860290dc901af5b4c2", size = 581242350, upload-time = "2025-06-05T20:04:51.979Z" }, { url = "https://files.pythonhosted.org/packages/45/a1/a17fade6567c57452cfc8f967a40d1035bb9301db52f27808167fbb2be2f/nvidia_cublas_cu12-12.9.1.4-py3-none-win_amd64.whl", hash = "sha256:1e5fee10662e6e52bd71dec533fbbd4971bb70a5f24f3bc3793e5c2e9dc640bf", size = 553153899, upload-time = "2025-06-05T20:13:35.556Z" }, ] @@ -5967,16 +5638,11 @@ name = "nvidia-cuda-runtime-cu12" version = "12.8.90" source = { registry = "https://pypi.org/simple" } resolution-markers = [ - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] wheels = [ { url = "https://files.pythonhosted.org/packages/7c/75/f865a3b236e4647605ea34cc450900854ba123834a5f1598e160b9530c3a/nvidia_cuda_runtime_cu12-12.8.90-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:52bf7bbee900262ffefe5e9d5a2a69a30d97e2bc5bb6cc866688caa976966e3d", size = 965265, upload-time = "2025-03-07T01:39:43.533Z" }, @@ -6006,6 +5672,7 @@ resolution-markers = [ ] wheels = [ { url = "https://files.pythonhosted.org/packages/bc/e0/0279bd94539fda525e0c8538db29b72a5a8495b0c12173113471d28bce78/nvidia_cuda_runtime_cu12-12.9.79-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:83469a846206f2a733db0c42e223589ab62fd2fabac4432d2f8802de4bded0a4", size = 3515012, upload-time = "2025-06-05T20:00:35.519Z" }, + { url = "https://files.pythonhosted.org/packages/bc/46/a92db19b8309581092a3add7e6fceb4c301a3fd233969856a8cbf042cd3c/nvidia_cuda_runtime_cu12-12.9.79-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:25bba2dfb01d48a9b59ca474a1ac43c6ebf7011f1b0b8cc44f54eb6ac48a96c3", size = 3493179, upload-time = "2025-06-05T20:00:53.735Z" }, { url = "https://files.pythonhosted.org/packages/59/df/e7c3a360be4f7b93cee39271b792669baeb3846c58a4df6dfcf187a7ffab/nvidia_cuda_runtime_cu12-12.9.79-py3-none-win_amd64.whl", hash = "sha256:8e018af8fa02363876860388bd10ccb89eb9ab8fb0aa749aaf58430a9f7c4891", size = 3591604, upload-time = "2025-06-05T20:11:17.036Z" }, ] @@ -6014,7 +5681,7 @@ name = "nvidia-cudnn-cu12" version = "9.10.2.21" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-cublas-cu12", version = "12.8.4.1", source = { registry = "https://pypi.org/simple" }, marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, + { name = "nvidia-cublas-cu12", version = "12.8.4.1", source = { registry = "https://pypi.org/simple" }, marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/ba/51/e123d997aa098c61d029f76663dedbfb9bc8dcf8c60cbd6adbe42f76d049/nvidia_cudnn_cu12-9.10.2.21-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:949452be657fa16687d0930933f032835951ef0892b37d2d53824d1a84dc97a8", size = 706758467, upload-time = "2025-06-06T21:54:08.597Z" }, @@ -6025,7 +5692,7 @@ name = "nvidia-cufft-cu12" version = "11.3.3.83" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-nvjitlink-cu12", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, + { name = "nvidia-nvjitlink-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/1f/13/ee4e00f30e676b66ae65b4f08cb5bcbb8392c03f54f2d5413ea99a5d1c80/nvidia_cufft_cu12-11.3.3.83-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:4d2dd21ec0b88cf61b62e6b43564355e5222e4a3fb394cac0db101f2dd0d4f74", size = 193118695, upload-time = "2025-03-07T01:45:27.821Z" }, @@ -6052,9 +5719,9 @@ name = "nvidia-cusolver-cu12" version = "11.7.3.90" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-cublas-cu12", version = "12.8.4.1", source = { registry = "https://pypi.org/simple" }, marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, - { name = "nvidia-cusparse-cu12", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, - { name = "nvidia-nvjitlink-cu12", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, + { name = "nvidia-cublas-cu12", version = "12.8.4.1", source = { registry = "https://pypi.org/simple" }, marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, + { name = "nvidia-cusparse-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, + { name = "nvidia-nvjitlink-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/85/48/9a13d2975803e8cf2777d5ed57b87a0b6ca2cc795f9a4f59796a910bfb80/nvidia_cusolver_cu12-11.7.3.90-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:4376c11ad263152bd50ea295c05370360776f8c3427b30991df774f9fb26c450", size = 267506905, upload-time = "2025-03-07T01:47:16.273Z" }, @@ -6065,7 +5732,7 @@ name = "nvidia-cusparse-cu12" version = "12.5.8.93" source = { registry = "https://pypi.org/simple" } dependencies = [ - { name = "nvidia-nvjitlink-cu12", marker = "platform_machine == 'x86_64' and sys_platform == 'linux'" }, + { name = "nvidia-nvjitlink-cu12", marker = "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')" }, ] wheels = [ { url = "https://files.pythonhosted.org/packages/c2/f5/e1854cb2f2bcd4280c44736c93550cc300ff4b8c95ebe370d0aa7d2b473d/nvidia_cusparse_cu12-12.5.8.93-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:1ec05d76bbbd8b61b06a80e1eaf8cf4959c3d4ce8e711b65ebd0443bb0ebb13b", size = 288216466, upload-time = "2025-03-07T01:48:13.779Z" }, @@ -6580,8 +6247,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "typing-extensions", marker = "python_full_version < '3.11'" }, @@ -6604,18 +6270,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "typing-extensions", marker = "python_full_version >= '3.11' and python_full_version < '3.13'" }, @@ -6841,8 +6503,7 @@ source = { registry = "https://pypi.org/simple" } resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "(python_full_version < '3.11' and platform_machine != 'aarch64') or (python_full_version < '3.11' and sys_platform != 'linux')" }, @@ -6911,17 +6572,13 @@ resolution-markers = [ "python_full_version == '3.12.*' and sys_platform == 'darwin'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "(python_full_version >= '3.11' and platform_machine != 'aarch64') or (python_full_version >= '3.11' and sys_platform != 'linux')" }, @@ -7221,19 +6878,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" @@ -7737,20 +7381,6 @@ wheels = [ { url = "https://files.pythonhosted.org/packages/3a/d8/a211b3f85e99a0daa2ddec96c949cac6824bd305b040571b82a03dd62636/pycodestyle-2.12.1-py2.py3-none-any.whl", hash = "sha256:46f0fb92069a7c28ab7bb558f05bfc0110dac69a0cd23c61ea0040283a9d78b3", size = 31284, upload-time = "2024-08-04T20:26:53.173Z" }, ] -[[package]] -name = "pycollada" -version = "0.9.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 = "python-dateutil" }, -] -sdist = { url = "https://files.pythonhosted.org/packages/5a/8d/52a5364a17eb96129962cae8d3ee7658775e085ad0ba38388684ad5944e9/pycollada-0.9.3.tar.gz", hash = "sha256:c34d6dcf0fe2eba5896f71c96d37a1c0fe1a61f08440fa0cfcec3dc2895d3302", size = 110826, upload-time = "2026-01-24T15:45:23.625Z" } -wheels = [ - { url = "https://files.pythonhosted.org/packages/07/86/f1f61b7a0701f9d1299e5293d083318019f91021a4d449f94d59dbe024e4/pycollada-0.9.3-py3-none-any.whl", hash = "sha256:636e6496f60987586db82455ea7bbd9ade775e8181c6590c83b698b6cd53a9f5", size = 129206, upload-time = "2026-01-24T15:45:22.182Z" }, -] - [[package]] name = "pycparser" version = "3.0" @@ -8867,7 +8497,7 @@ wheels = [ [[package]] name = "rerun-sdk" -version = "0.30.2" +version = "0.29.2" source = { registry = "https://pypi.org/simple" } dependencies = [ { name = "attrs" }, @@ -8878,10 +8508,10 @@ dependencies = [ { name = "typing-extensions" }, ] wheels = [ - { url = "https://files.pythonhosted.org/packages/79/37/0bd89c08fec35b3b23f0ca38eff0fd9960c67734643730b45210b407e35d/rerun_sdk-0.30.2-cp310-abi3-macosx_11_0_arm64.whl", hash = "sha256:8d952bf7ae2a1b1ee6064435cc14c82858771c2c2f1ec48b8164d69f6e4f0708", size = 114280633, upload-time = "2026-03-11T10:10:03.535Z" }, - { url = "https://files.pythonhosted.org/packages/88/1b/ffa0335499343894648fa92cd655978a65de0f2c6fc2ddca9fe6b6f9c242/rerun_sdk-0.30.2-cp310-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:f9bbe66ba4e9532c1a062d2d488ba09009c2231441fcfb013454832a9bd1bdfb", size = 122292152, upload-time = "2026-03-11T10:10:13.558Z" }, - { url = "https://files.pythonhosted.org/packages/c5/89/182ef62bff3d9f190dd2e024b28cf0513ac7a83bc15b979e052c46c41f64/rerun_sdk-0.30.2-cp310-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:f3480847f124894d1c9bcbbdb4182a4c64986bf9d0d669e10752f0738ecac359", size = 127332181, upload-time = "2026-03-11T10:10:21.713Z" }, - { url = "https://files.pythonhosted.org/packages/71/85/d04383cb508970ab8e9d9004e1f5959c5de8cba1efa47de20f9a94912dd2/rerun_sdk-0.30.2-cp310-abi3-win_amd64.whl", hash = "sha256:87bef55c6fccdcc9c3b6ff377a68f465ab872ffc1d16184abb62a382b63668a0", size = 110063998, upload-time = "2026-03-11T10:10:30.277Z" }, + { url = "https://files.pythonhosted.org/packages/ad/d1/6b31d12e726732dced50806b1cb0b5fb55c478ee4ac23d68f50db888cf2c/rerun_sdk-0.29.2-cp310-abi3-macosx_11_0_arm64.whl", hash = "sha256:ead2b4bb93cac553c9b524442e49ba5f34c30ab9db2225e1ed2ce2ee235ea46b", size = 112371441, upload-time = "2026-02-12T19:31:07.296Z" }, + { url = "https://files.pythonhosted.org/packages/dc/81/9b3619b37c8a7492ccbe9ea172dedc5ffb66b83ded82b8f443c1958fe1c0/rerun_sdk-0.29.2-cp310-abi3-manylinux_2_28_aarch64.whl", hash = "sha256:a97f5601cb50c14ec665525c0cf65056167de1306958a0526ff1e8d384320076", size = 120304992, upload-time = "2026-02-12T19:31:12.499Z" }, + { url = "https://files.pythonhosted.org/packages/63/43/2590293ce7985cbb88f9fdd67b90c36b954116f6c75639b378f098b3ff61/rerun_sdk-0.29.2-cp310-abi3-manylinux_2_28_x86_64.whl", hash = "sha256:392a7f2c3db660716b660f4b164f9b73a076100378781a3a2551edf290d00c23", size = 125305451, upload-time = "2026-02-12T19:31:17.319Z" }, + { url = "https://files.pythonhosted.org/packages/bc/06/b73e04344f2220d48c0583270a54873bca3b93ab476cf09629941afac8e5/rerun_sdk-0.29.2-cp310-abi3-win_amd64.whl", hash = "sha256:a3ccfbac8df89519a075f9dc3499a9e715c653a19a17de00d39fd218a589e009", size = 108289765, upload-time = "2026-02-12T19:31:22.616Z" }, ] [[package]] @@ -9067,22 +8697,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" @@ -9143,8 +8757,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "joblib", marker = "python_full_version < '3.11'" }, @@ -9199,18 +8812,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "joblib", marker = "python_full_version >= '3.11'" }, @@ -9266,8 +8875,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.2.6", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, @@ -9334,18 +8942,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "numpy", version = "2.3.5", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version >= '3.11'" }, @@ -9422,8 +9026,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "optype", version = "0.9.3", source = { registry = "https://pypi.org/simple" }, marker = "python_full_version < '3.11'" }, @@ -9446,18 +9049,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "optype", version = "0.16.0", source = { registry = "https://pypi.org/simple" }, extra = ["numpy"], marker = "python_full_version >= '3.11'" }, @@ -9498,74 +9097,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" @@ -9793,15 +9324,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" @@ -9877,8 +9399,7 @@ resolution-markers = [ "python_full_version < '3.11' and sys_platform == 'darwin'", "python_full_version < '3.11' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version < '3.11' and sys_platform == 'win32'", - "python_full_version < '3.11' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version < '3.11' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version < '3.11' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version < '3.11' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "ml-dtypes", marker = "python_full_version < '3.11'" }, @@ -9921,18 +9442,14 @@ resolution-markers = [ "python_full_version == '3.12.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version >= '3.14' and sys_platform == 'win32'", "python_full_version == '3.13.*' and sys_platform == 'win32'", - "python_full_version >= '3.14' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version >= '3.14' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", - "python_full_version == '3.13.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version >= '3.14' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version >= '3.14' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.13.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.13.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.12.*' and sys_platform == 'win32'", - "python_full_version == '3.12.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.12.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.12.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", "python_full_version == '3.11.*' and sys_platform == 'darwin'", "python_full_version == '3.11.*' and platform_machine == 'aarch64' and sys_platform == 'linux'", "python_full_version == '3.11.*' and sys_platform == 'win32'", - "python_full_version == '3.11.*' and platform_machine == 'x86_64' and sys_platform == 'linux'", - "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and platform_machine != 'x86_64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", + "(python_full_version == '3.11.*' and platform_machine != 'aarch64' and sys_platform == 'linux') or (python_full_version == '3.11.*' and sys_platform != 'darwin' and sys_platform != 'linux' and sys_platform != 'win32')", ] dependencies = [ { name = "ml-dtypes", marker = "python_full_version >= '3.11'" }, @@ -10407,40 +9924,24 @@ 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" source = { registry = "https://pypi.org/simple" } wheels = [ + { url = "https://files.pythonhosted.org/packages/44/ba/b1b04f4b291a3205d95ebd24465de0e5bf010a2df27a4e58a9b5f039d8f2/triton-3.6.0-cp310-cp310-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:6c723cfb12f6842a0ae94ac307dba7e7a44741d720a40cf0e270ed4a4e3be781", size = 175972180, upload-time = "2026-01-20T16:15:53.664Z" }, { url = "https://files.pythonhosted.org/packages/8c/f7/f1c9d3424ab199ac53c2da567b859bcddbb9c9e7154805119f8bd95ec36f/triton-3.6.0-cp310-cp310-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a6550fae429e0667e397e5de64b332d1e5695b73650ee75a6146e2e902770bea", size = 188105201, upload-time = "2026-01-20T16:00:29.272Z" }, + { url = "https://files.pythonhosted.org/packages/0f/2c/96f92f3c60387e14cc45aed49487f3486f89ea27106c1b1376913c62abe4/triton-3.6.0-cp311-cp311-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:49df5ef37379c0c2b5c0012286f80174fcf0e073e5ade1ca9a86c36814553651", size = 176081190, upload-time = "2026-01-20T16:16:00.523Z" }, { url = "https://files.pythonhosted.org/packages/e0/12/b05ba554d2c623bffa59922b94b0775673de251f468a9609bc9e45de95e9/triton-3.6.0-cp311-cp311-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:e8e323d608e3a9bfcc2d9efcc90ceefb764a82b99dea12a86d643c72539ad5d3", size = 188214640, upload-time = "2026-01-20T16:00:35.869Z" }, + { url = "https://files.pythonhosted.org/packages/17/5d/08201db32823bdf77a0e2b9039540080b2e5c23a20706ddba942924ebcd6/triton-3.6.0-cp312-cp312-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:374f52c11a711fd062b4bfbb201fd9ac0a5febd28a96fb41b4a0f51dde3157f4", size = 176128243, upload-time = "2026-01-20T16:16:07.857Z" }, { url = "https://files.pythonhosted.org/packages/ab/a8/cdf8b3e4c98132f965f88c2313a4b493266832ad47fb52f23d14d4f86bb5/triton-3.6.0-cp312-cp312-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:74caf5e34b66d9f3a429af689c1c7128daba1d8208df60e81106b115c00d6fca", size = 188266850, upload-time = "2026-01-20T16:00:43.041Z" }, + { url = "https://files.pythonhosted.org/packages/3c/12/34d71b350e89a204c2c7777a9bba0dcf2f19a5bfdd70b57c4dbc5ffd7154/triton-3.6.0-cp313-cp313-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:448e02fe6dc898e9e5aa89cf0ee5c371e99df5aa5e8ad976a80b93334f3494fd", size = 176133521, upload-time = "2026-01-20T16:16:13.321Z" }, { url = "https://files.pythonhosted.org/packages/f9/0b/37d991d8c130ce81a8728ae3c25b6e60935838e9be1b58791f5997b24a54/triton-3.6.0-cp313-cp313-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:10c7f76c6e72d2ef08df639e3d0d30729112f47a56b0c81672edc05ee5116ac9", size = 188289450, upload-time = "2026-01-20T16:00:49.136Z" }, + { url = "https://files.pythonhosted.org/packages/ce/4e/41b0c8033b503fd3cfcd12392cdd256945026a91ff02452bef40ec34bee7/triton-3.6.0-cp313-cp313t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1722e172d34e32abc3eb7711d0025bb69d7959ebea84e3b7f7a341cd7ed694d6", size = 176276087, upload-time = "2026-01-20T16:16:18.989Z" }, { url = "https://files.pythonhosted.org/packages/35/f8/9c66bfc55361ec6d0e4040a0337fb5924ceb23de4648b8a81ae9d33b2b38/triton-3.6.0-cp313-cp313t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:d002e07d7180fd65e622134fbd980c9a3d4211fb85224b56a0a0efbd422ab72f", size = 188400296, upload-time = "2026-01-20T16:00:56.042Z" }, + { url = "https://files.pythonhosted.org/packages/49/55/5ecf0dcaa0f2fbbd4420f7ef227ee3cb172e91e5fede9d0ecaddc43363b4/triton-3.6.0-cp314-cp314-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:ef5523241e7d1abca00f1d240949eebdd7c673b005edbbce0aca95b8191f1d43", size = 176138577, upload-time = "2026-01-20T16:16:25.426Z" }, { url = "https://files.pythonhosted.org/packages/df/3d/9e7eee57b37c80cec63322c0231bb6da3cfe535a91d7a4d64896fcb89357/triton-3.6.0-cp314-cp314-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:a17a5d5985f0ac494ed8a8e54568f092f7057ef60e1b0fa09d3fd1512064e803", size = 188273063, upload-time = "2026-01-20T16:01:07.278Z" }, + { url = "https://files.pythonhosted.org/packages/48/db/56ee649cab5eaff4757541325aca81f52d02d4a7cd3506776cad2451e060/triton-3.6.0-cp314-cp314t-manylinux_2_27_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:0b3a97e8ed304dfa9bd23bb41ca04cdf6b2e617d5e782a8653d616037a5d537d", size = 176274804, upload-time = "2026-01-20T16:16:31.528Z" }, { url = "https://files.pythonhosted.org/packages/f6/56/6113c23ff46c00aae423333eb58b3e60bdfe9179d542781955a5e1514cb3/triton-3.6.0-cp314-cp314t-manylinux_2_27_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:46bd1c1af4b6704e554cad2eeb3b0a6513a980d470ccfa63189737340c7746a7", size = 188397994, upload-time = "2026-01-20T16:01:14.236Z" }, ] @@ -10875,28 +10376,6 @@ 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" @@ -10995,60 +10474,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" @@ -11064,29 +10489,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" @@ -11621,22 +11023,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 d03982092f79e93869b32a3e5af7e8f6a3be5cb0 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 6 May 2026 22:37:06 +0200 Subject: [PATCH 07/23] fix: restore dev's unitree_go2 drive_train (accidentally deleted in cleanup) --- .../drive_trains/unitree_go2/README.md | 69 ++ .../drive_trains/unitree_go2/adapter.py | 691 ++++++++++++++++++ 2 files changed, 760 insertions(+) create mode 100644 dimos/hardware/drive_trains/unitree_go2/README.md create mode 100644 dimos/hardware/drive_trains/unitree_go2/adapter.py diff --git a/dimos/hardware/drive_trains/unitree_go2/README.md b/dimos/hardware/drive_trains/unitree_go2/README.md new file mode 100644 index 0000000000..dea50cf728 --- /dev/null +++ b/dimos/hardware/drive_trains/unitree_go2/README.md @@ -0,0 +1,69 @@ +# Unitree Go2 drive-train adapter + +[`adapter.py`](adapter.py) — `UnitreeGo2TwistAdapter` (high-level): Twist `(vx, vy, wz)` via SportClient, with optional Rage Mode (`rage_mode=True`, ~2.5 m/s forward envelope). Auto-registered as `"unitree_go2"` and used by blueprints like `unitree-go2-keyboard-teleop`. This is the one you want for teleop, navigation, or anything velocity-commanded. + +--- + +## Running + +Build the CycloneDDS C library via nix (once per machine — creates +`./result` symlink at the repo root, which acts as a GC root): + +```bash +nix build nixpkgs#cyclonedds +``` + +Point your shell / venv at it so `cyclonedds-python` can find the C +library at install and runtime. Easiest: append to `.venv/bin/activate` +so it's set every time you activate the venv: + +```bash +cat >> .venv/bin/activate < float: + return lo if x < lo else hi if x > hi else x + + +@dataclass +class _Session: + """Active connection state for a Go2. + + The session object is created by connect() and set on the adapter under + _session_lock. All mutable state that can be touched by both the DDS + callback thread and the control thread lives here, guarded by `lock`. + """ + + client: SportClient + motion_switcher: MotionSwitcherClient + lock: threading.Lock + state_sub: ChannelSubscriber | None = None + latest_state: SportModeState_ | None = None + enabled: bool = False + locomotion_ready: bool = False + + # Rage Mode joystick publisher (rt/wirelesscontroller_unprocessed path) + rage_active: bool = False + rage_pub: ChannelPublisher | None = None + rage_thread: threading.Thread | None = None + rage_stop: threading.Event | None = None + rage_cmd: tuple[float, float, float] = (0.0, 0.0, 0.0) + + +class UnitreeGo2TwistAdapter: + """TwistBaseAdapter for the Unitree Go2 quadruped via unitree_sdk2py (DDS). + + 3 DOF velocity: [vx, vy, wz]. + - vx: forward/backward linear velocity (m/s) + - vy: lateral (left positive) linear velocity (m/s) + - wz: yaw rate (rad/s) + + Thread model: + - _session_lock guards the self._session reference across threads. + - session.lock guards latest_state and SportClient RPC serialization. + Never take _session_lock while holding session.lock - the DDS callback + already holds session.lock briefly during state updates. + """ + + # AI-controller API ID for the Rage Mode toggle. + _SPORT_API_ID_RAGEMODE: int = 2059 + + # Rage velocity envelope (m/s, m/s, rad/s) from rage_mode_export_cfg.json. + _RAGE_UP_VX: float = 2.5 + _RAGE_UP_VY: float = 1.0 + _RAGE_UP_VYAW: float = 5.0 + + _RAGE_PUBLISH_HZ: float = 100.0 + _RAGE_LY_SIGN: float = 1.0 # vx → ly + _RAGE_LX_SIGN: float = -1.0 # vy → lx + _RAGE_RX_SIGN: float = -1.0 # wz → rx + + def __init__( + self, + dof: int = 3, + speed_level: int = 1, + rage_mode: bool = False, + **_: Any, + ) -> None: + if dof != 3: + raise ValueError(f"Go2 only supports 3 DOF (vx, vy, wz), got {dof}") + + self._session: _Session | None = None + self._session_lock = threading.Lock() + self._speed_level = speed_level + self._rage_mode_default = rage_mode + self._last_guard_warn_ts: float = 0.0 + + def connect(self) -> bool: + """Connect to Go2, verify sport mode, stand up, enter FreeWalk. + + Sequence: + 1. ChannelFactoryInitialize(0) — default domain, default NIC. + 2. MotionSwitcher.Init + poll CheckMode() until a sport mode + is reported (DDS discovery) or _DISCOVERY_TIMEOUT_S elapses. + 3. Subscribe rt/sportmodestate for telemetry. + 4. SportClient.Init. + 5. _initialize_locomotion(): StandUp + FreeWalk + SpeedLevel. + 6. If rage_mode=True, set_rage_mode(True). + + Returns True on success, False on connect/init/locomotion + failure. On failure, logs guidance and the adapter stays in a + clean "not connected" state so a retry can succeed. + """ + with self._session_lock: + if self._session is not None: + logger.warning("[Go2] Already connected — disconnect first") + return False + + # ChannelFactoryInitialize raises if the factory already exists. + try: + ChannelFactoryInitialize(0) + except Exception: + pass + + motion_switcher = MotionSwitcherClient() + motion_switcher.SetTimeout(0.5) + motion_switcher.Init() + + # Poll CheckMode() through DDS discovery + mode = "" + for _ in range(50): + try: + code, data = motion_switcher.CheckMode() + except (OSError, RuntimeError, TimeoutError): + time.sleep(0.1) + continue + if code == 0 and isinstance(data, dict): + mode = (data.get("name") or "").strip() + if mode: + break + time.sleep(0.1) + motion_switcher.SetTimeout(5.0) + if not mode: + logger.error("[Go2] No sport mode active") + return False + logger.info(f"[Go2] Sport mode '{mode}' active") + + client = SportClient() + client.SetTimeout(10.0) + + session = _Session( + client=client, + motion_switcher=motion_switcher, + lock=threading.Lock(), + ) + + def state_callback(msg: SportModeState_) -> None: + with session.lock: + session.latest_state = msg + + state_sub = ChannelSubscriber("rt/sportmodestate", SportModeState_) + state_sub.Init(state_callback, 10) + session.state_sub = state_sub + + with self._session_lock: + self._session = session + + # disconnect() must run on any failure + try: + client.Init() + logger.info("[Go2] Connected") + + if not self._initialize_locomotion(): + logger.error("[Go2] Failed to initialize locomotion mode") + self.disconnect() + return False + + if self._rage_mode_default and not self.set_rage_mode(True): + logger.warning("[Go2] Rage Mode enable failed — continuing with regular locomotion") + except Exception: + self.disconnect() + raise + + return True + + def disconnect(self) -> None: + """Stop motion, stand the robot down, and tear down DDS resources. + + Safe to call multiple times. Explicitly Close()s the state + subscriber to prevent DDS reader leaks across reconnects. + """ + with self._session_lock: + session = self._session + self._session = None + + if session is None: + return + + self._stop_rage_joystick(session) + try: + with session.lock: + session.client.StopMove() + with session.lock: + session.client.StandDown() + except (OSError, RuntimeError, TimeoutError) as e: + logger.error(f"[Go2] Error during disconnect: {e}") + + if session.state_sub is not None: + try: + session.state_sub.Close() + except (OSError, RuntimeError) as e: + logger.error(f"[Go2] Error closing state subscriber: {e}") + + def is_connected(self) -> bool: + with self._session_lock: + return self._session is not None + + def get_dof(self) -> int: + """Always 3 for Go2 (vx, vy, wz).""" + return 3 + + def read_velocities(self) -> list[float]: + """Measured velocities [vx, vy, wz] from SportModeState_. + + Sources: + vx, vy: state.velocity[0], state.velocity[1] + wz: state.imu_state.gyroscope[2] + + Returns [0.0, 0.0, 0.0] during the startup gap before the first + DDS callback has populated latest_state. + """ + session = self._get_session() + with session.lock: + if session.latest_state is None: + return [0.0, 0.0, 0.0] + state = session.latest_state + return [ + float(state.velocity[0]), + float(state.velocity[1]), + float(state.imu_state.gyroscope[2]), + ] + + def read_odometry(self) -> list[float] | None: + """Measured pose [x, y, theta] from SportModeState_. + + Sources: + x, y: state.position[0], state.position[1] + theta: state.imu_state.rpy[2] (yaw) + + Returns None if no state message has arrived yet. + """ + session = self._get_session() + with session.lock: + if session.latest_state is None: + return None + state = session.latest_state + return [ + float(state.position[0]), + float(state.position[1]), + float(state.imu_state.rpy[2]), + ] + + def write_velocities(self, velocities: list[float]) -> bool: + """Send a Twist command [vx, vy, wz] to the Go2. + + When Rage Mode is active, the command is stashed in + session.rage_cmd and the 100 Hz joystick publisher thread picks + it up on its next tick (Rage's FSM ignores SportClient.Move). + Otherwise the command is forwarded directly via + SportClient.Move() → FsmFreeWalk. + + Refuses (returns False) if: + - len(velocities) != 3 + - session not enabled (write_enable(True) not called) + - locomotion not ready (StandUp/FreeWalk incomplete) + + Guard warnings are rate-limited to 1 Hz since this is called + at 100 Hz from the tick loop. + """ + if len(velocities) != 3: + return False + + session = self._get_session() + + if not session.enabled: + self._warn_guard("Not enabled, ignoring velocity command") + return False + + if not session.locomotion_ready: + self._warn_guard("Locomotion not ready, ignoring velocity command") + return False + + vx, vy, wz = velocities + + if session.rage_active: + session.rage_cmd = (vx, vy, wz) + return True + + return self._send_velocity(vx, vy, wz) + + def _warn_guard(self, msg: str) -> None: + """Rate-limited guard warning (at most once per second). + + write_velocities runs at 100 Hz from the tick loop; without + throttling, a sustained guard miss would emit 100 warnings/s. + """ + now = time.monotonic() + if now - self._last_guard_warn_ts < 1.0: + return + self._last_guard_warn_ts = now + logger.warning(f"[Go2] {msg}") + + def write_stop(self) -> bool: + """Stop motion via SportClient.StopMove(). Leaves robot standing.""" + session = self._get_session() + with session.lock: + session.client.StopMove() + return True + + def write_enable(self, enable: bool) -> bool: + """Enable/disable velocity command path. + + enable=True: ensures locomotion is ready (re-initializes if needed), + then flips session.enabled. + enable=False: calls write_stop() and clears session.enabled. Does + NOT stand the robot down — use disconnect() for that. + """ + session = self._get_session() + + if enable: + if not session.locomotion_ready: + if not self._initialize_locomotion(): + logger.error("[Go2] Failed to initialize locomotion") + return False + session.enabled = True + logger.info("[Go2] Enabled") + return True + + self.write_stop() + session.enabled = False + logger.info("[Go2] Disabled") + return True + + def read_enabled(self) -> bool: + with self._session_lock: + return self._session is not None and self._session.enabled + + def check_mode(self) -> str | None: + """Return the current MotionSwitcher mode name, or None on RPC fail. + + Wraps MotionSwitcher.CheckMode(). Empty string means no controller + active; None means the RPC returned a non-zero code or non-dict data. + """ + session = self._get_session() + code, data = session.motion_switcher.CheckMode() + if code == 0 and isinstance(data, dict): + return (data.get("name") or "").strip() + return None + + def get_sport_state(self) -> SportModeState_ | None: + """Return the latest SportModeState_ snapshot for diagnostics. + + Returned object is the live SDK message — do not mutate it. None + if no state message has arrived. + """ + session = self._get_session() + with session.lock: + return session.latest_state + + def get_status(self) -> dict[str, Any]: + """One-shot snapshot of adapter + robot state""" + with self._session_lock: + session = self._session + + if session is None: + return { + "connected": False, + "mode": None, + "enabled": False, + "locomotion_ready": False, + "rage_active": False, + "speed_level": self._speed_level, + "has_state": False, + "velocity": None, + "position": None, + "body_height": None, + "sport_mode_num": None, + } + + mode = self.check_mode() + + with session.lock: + state = session.latest_state + enabled = session.enabled + locomotion_ready = session.locomotion_ready + rage_active = session.rage_active + + velocity: list[float] | None = None + position: list[float] | None = None + body_height: float | None = None + sport_mode_num: int | None = None + + if state is not None: + try: + velocity = [ + float(state.velocity[0]), + float(state.velocity[1]), + float(state.imu_state.gyroscope[2]), + ] + position = [ + float(state.position[0]), + float(state.position[1]), + float(state.imu_state.rpy[2]), + ] + body_height = float(state.body_height) + sport_mode_num = int(state.mode) + except (AttributeError, IndexError, TypeError, ValueError): + pass + + return { + "connected": True, + "mode": mode, + "enabled": enabled, + "locomotion_ready": locomotion_ready, + "rage_active": rage_active, + "speed_level": self._speed_level, + "has_state": state is not None, + "velocity": velocity, + "position": position, + "body_height": body_height, + "sport_mode_num": sport_mode_num, + } + + def set_speed_level(self, level: int) -> bool: + """Set the SportClient speed envelope at runtime. + + Go2 SDK convention: -1 = slow, 0 = normal, 1 = fast (max). When + Rage is active, the Rage envelope (_RAGE_UP_VX etc.) applies + instead. Updates self._speed_level so subsequent + _initialize_locomotion() calls apply the same level. + + Returns True if the RPC returned 0. + """ + session = self._get_session() + with session.lock: + ret = session.client.SpeedLevel(level) + + if ret != 0: + logger.warning(f"[Go2] SpeedLevel({level}) returned {ret}") + return False + + self._speed_level = level + logger.info(f"[Go2] SpeedLevel set to {level}") + return True + + def set_rage_mode(self, enable: bool) -> bool: + """Toggle Rage Mode (api_id 2059) — widens forward envelope to ~2.5 m/s. + + Velocity input flows via rt/wirelesscontroller_unprocessed, not + SportClient.Move (FsmRageMode isn't in AiController::Move's dispatch). + Idempotent. Returns True on 2059 success; publisher/SwitchJoystick + failures are logged but don't fail the call. + """ + session = self._get_session() + + if session.rage_active == enable: + return True + + with session.lock: + ret = session.client.BalanceStand() + if ret != 0: + # Non-zero is usually benign here (already balanced / FSM transition + # in progress) — only fatal if the rage toggle below also fails. + logger.info(f"[Go2] BalanceStand returned {ret} (likely already balanced — proceeding)") + time.sleep(0.3) + + if not self._call_sport_api(self._SPORT_API_ID_RAGEMODE, {"data": enable}): + return False + + if enable: + time.sleep(2.0) # let FsmRageMode transition settle + self._start_rage_joystick(session) + with session.lock: + sj_ret = session.client.SwitchJoystick(True) + if sj_ret != 0: + logger.warning(f"[Go2] SwitchJoystick(True) after rage returned {sj_ret}") + else: + self._stop_rage_joystick(session) + with session.lock: + sj_ret = session.client.SwitchJoystick(False) + if sj_ret != 0: + logger.warning(f"[Go2] SwitchJoystick(False) after rage returned {sj_ret}") + + logger.info(f"[Go2] Rage Mode {'enabled' if enable else 'disabled'}") + return True + + def _start_rage_joystick(self, session: _Session) -> None: + """Create the WirelessController publisher and spawn the 100Hz thread.""" + if session.rage_pub is not None: + return + pub = ChannelPublisher("rt/wirelesscontroller_unprocessed", WirelessController_) + pub.Init() + session.rage_pub = pub + + session.rage_stop = threading.Event() + session.rage_cmd = (0.0, 0.0, 0.0) + session.rage_active = True + session.rage_thread = threading.Thread( + target=self._rage_joystick_loop, + args=(session,), + name="go2-rage-joystick", + daemon=True, + ) + session.rage_thread.start() + + def _stop_rage_joystick(self, session: _Session) -> None: + """Stop the publisher thread and release the DDS writer. + + Closes ChannelPublisher explicitly to avoid leaking the DDS writer + across repeated set_rage_mode(True/False) cycles. + """ + session.rage_active = False + if session.rage_stop is not None: + session.rage_stop.set() + if session.rage_thread is not None: + session.rage_thread.join(timeout=1.0) + session.rage_thread = None + session.rage_stop = None + if session.rage_pub is not None: + try: + session.rage_pub.Close() + except (OSError, RuntimeError) as e: + logger.warning(f"[Go2] Rage publisher Close raised: {e}") + session.rage_pub = None + + def _rage_joystick_loop(self, session: _Session) -> None: + """Publish the latest rage_cmd as a WirelessController_ message. + + Runs at _RAGE_PUBLISH_HZ. On each tick, reads session.rage_cmd, + normalizes to stick axes via the envelope constants, and writes + a WirelessController_ message. Exits when rage_stop is set or + the session's publisher is torn down. + """ + period = 1.0 / self._RAGE_PUBLISH_HZ + msg = unitree_go_msg_dds__WirelessController_() + msg.keys = 0 + msg.ry = 0.0 + + while session.rage_stop is not None and not session.rage_stop.wait(period): + pub = session.rage_pub + if pub is None: + return + vx, vy, wz = session.rage_cmd + + ly = _clip(vx / self._RAGE_UP_VX, -1.0, 1.0) * self._RAGE_LY_SIGN + lx = _clip(vy / self._RAGE_UP_VY, -1.0, 1.0) * self._RAGE_LX_SIGN + rx = _clip(wz / self._RAGE_UP_VYAW, -1.0, 1.0) * self._RAGE_RX_SIGN + + msg.lx = float(lx) + msg.ly = float(ly) + msg.rx = float(rx) + + try: + pub.Write(msg) + except (OSError, RuntimeError) as e: + logger.warning(f"[Go2] Rage joystick publish raised: {e}") + return + + def _call_sport_api(self, api_id: int, payload: dict[str, Any] | None = None) -> bool: + """Generic escape hatch for undocumented mcf sport API IDs. + + SportClient's internal dispatcher rejects unregistered api_ids + with code 3103 (RPC_ERR_CLIENT_API_NOT_REG) before any message + leaves the process — the public SDK only registers its named + methods in __init__. We call _RegistApi() first (idempotent dict + set) so undocumented IDs like RAGEMODE reach the robot. + + Uses leading-underscore SDK methods (_RegistApi, _Call) — these + are not part of the public SDK contract. Verified working against + unitree-sdk2py-dimos>=1.0.2; retest if the SDK is upgraded. + + Returns True on RPC code 0. On failure, logs code + response. + """ + session = self._get_session() + body = json.dumps(payload or {}) + with session.lock: + session.client._RegistApi(api_id, 0) + code, data = session.client._Call(api_id, body) + + if code != 0: + logger.warning(f"[Go2] _Call({api_id}, {body}) -> code={code} data={data!r}") + return False + return True + + def _get_session(self) -> _Session: + """Return active session or raise RuntimeError if disconnected. + + Note: callers using the returned session.lock must NEVER then + try to acquire self._session_lock — see the lock-ordering rule + in the class docstring. + """ + session = self._session + if session is None: + raise RuntimeError("Go2 not connected") + return session + + def _initialize_locomotion(self) -> bool: + """StandUp → 3s settle → FreeWalk → 2s settle → SpeedLevel. + + Called from connect() and from write_enable(True) if locomotion + was not yet ready. Assumes a sport mode is already active. + """ + session = self._get_session() + + if not self.check_mode(): + logger.error("[Go2] No sport mode active") + return False + + logger.info("[Go2] Standing up...") + with session.lock: + ret = session.client.StandUp() + if ret != 0: + logger.error(f"[Go2] StandUp failed with code {ret}") + return False + time.sleep(3) + + logger.info("[Go2] Activating FreeWalk...") + with session.lock: + ret = session.client.FreeWalk() + if ret != 0: + logger.error(f"[Go2] FreeWalk failed with code {ret}") + return False + time.sleep(2) + + with session.lock: + sl_ret = session.client.SpeedLevel(self._speed_level) + if sl_ret == 0: + logger.info(f"[Go2] SpeedLevel({self._speed_level}) applied") + else: + logger.warning(f"[Go2] SpeedLevel({self._speed_level}) returned {sl_ret}") + + session.locomotion_ready = True + logger.info("[Go2] Locomotion ready") + return True + + def _send_velocity(self, vx: float, vy: float, wz: float) -> bool: + session = self._get_session() + with session.lock: + ret = session.client.Move(vx, vy, wz) + if ret != 0: + logger.warning(f"[Go2] Move() returned code {ret}") + return False + return True + + +def register(registry: TwistBaseAdapterRegistry) -> None: + registry.register("unitree_go2", UnitreeGo2TwistAdapter) + + +__all__ = ["UnitreeGo2TwistAdapter"] From 0ed6efbe2d372b3aaf8c0d37cfbfa3f929113987 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Wed, 6 May 2026 23:25:22 +0200 Subject: [PATCH 08/23] chore(g1-wbc): drop perception2/viser leaks + test file (defer to follow-up) --- dimos/control/tasks/test_groot_wbc_task.py | 463 --------------------- dimos/core/global_config.py | 1 - dimos/robot/unitree/g1/system_prompt.py | 5 - 3 files changed, 469 deletions(-) delete mode 100644 dimos/control/tasks/test_groot_wbc_task.py diff --git a/dimos/control/tasks/test_groot_wbc_task.py b/dimos/control/tasks/test_groot_wbc_task.py deleted file mode 100644 index bc6f5f9c9a..0000000000 --- a/dimos/control/tasks/test_groot_wbc_task.py +++ /dev/null @@ -1,463 +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. - -"""Unit tests for GrootWBCTask. - -ONNX runtime is monkey-patched with a stub that records which model -was called and returns a deterministic action — so the tests exercise -the obs-build, model-selection, decimation, and command-timeout logic -without depending on the actual GR00T ONNX weights. -""" - -from __future__ import annotations - -import math -from typing import Any -from unittest.mock import MagicMock - -import numpy as np -import pytest - -from dimos.control.components import make_humanoid_joints -from dimos.control.task import ( - ControlMode, - CoordinatorState, - JointStateSnapshot, -) -from dimos.control.tasks import groot_wbc_task -from dimos.control.tasks.groot_wbc_task import GrootWBCTask, GrootWBCTaskConfig -from dimos.hardware.whole_body.spec import IMUState - -# --------------------------------------------------------------------------- -# Fixtures -# --------------------------------------------------------------------------- - - -class _StubSession: - """ONNX InferenceSession stub that tracks call count and returns a fixed action.""" - - def __init__( - self, - model_path: str, - *, - label: str, - action: np.ndarray, - call_log: list[str], - ) -> None: - self.model_path = model_path - self._label = label - self._action = action - self._call_log = call_log - fake_input = MagicMock() - fake_input.name = "obs" - self._inputs = [fake_input] - - def get_inputs(self) -> list[Any]: - return self._inputs - - def run(self, _outputs: Any, _feed: dict[str, np.ndarray]) -> list[np.ndarray]: - self._call_log.append(self._label) - return [self._action.reshape(1, -1)] - - -@pytest.fixture -def patched_ort(monkeypatch): - """Patch onnxruntime so no real ONNX files are needed.""" - call_log: list[str] = [] - - def _factory(path: str, providers: Any = None) -> _StubSession: - label = "balance" if "balance" in str(path) else "walk" - return _StubSession( - str(path), - label=label, - action=np.full(15, 0.1, dtype=np.float32), - call_log=call_log, - ) - - monkeypatch.setattr(groot_wbc_task.ort, "InferenceSession", _factory) - monkeypatch.setattr( - groot_wbc_task.ort, "get_available_providers", lambda: ["CPUExecutionProvider"] - ) - return call_log - - -@pytest.fixture -def stub_adapter(): - """Stub WholeBodyAdapter returning a zeroed-out IMU (identity quat).""" - adapter = MagicMock() - adapter.read_imu.return_value = IMUState( - quaternion=(1.0, 0.0, 0.0, 0.0), # identity (w, x, y, z) - gyroscope=(0.0, 0.0, 0.0), - accelerometer=(0.0, 0.0, -9.81), - rpy=(0.0, 0.0, 0.0), - ) - return adapter - - -@pytest.fixture -def joints_29(): - return make_humanoid_joints("g1") - - -@pytest.fixture -def task(patched_ort, stub_adapter, joints_29) -> GrootWBCTask: - """Test fixture: auto-armed with no ramp so the existing policy - tests can run compute() immediately after start(). The arming/ - dry-run state-machine has its own dedicated tests below.""" - legs_waist = joints_29[:15] - return GrootWBCTask( - name="groot_wbc", - config=GrootWBCTaskConfig( - balance_onnx="/fake/balance.onnx", - walk_onnx="/fake/walk.onnx", - joint_names=legs_waist, - all_joint_names=joints_29, - priority=50, - auto_arm=True, - default_ramp_seconds=0.0, - ), - adapter=stub_adapter, - ) - - -@pytest.fixture -def unarmed_task(patched_ort, stub_adapter, joints_29) -> GrootWBCTask: - """Fixture mirroring the real-hardware blueprint: active but - unarmed on start(), so arm()/disarm()/set_dry_run() can be - exercised explicitly.""" - legs_waist = joints_29[:15] - return GrootWBCTask( - name="groot_wbc", - config=GrootWBCTaskConfig( - balance_onnx="/fake/balance.onnx", - walk_onnx="/fake/walk.onnx", - joint_names=legs_waist, - all_joint_names=joints_29, - priority=50, - auto_arm=False, - default_ramp_seconds=0.0, - ), - adapter=stub_adapter, - ) - - -def _state_at(t_now: float, joint_names: list[str]) -> CoordinatorState: - snap = JointStateSnapshot( - joint_positions={n: 0.0 for n in joint_names}, - joint_velocities={n: 0.0 for n in joint_names}, - joint_efforts={n: 0.0 for n in joint_names}, - timestamp=t_now, - ) - return CoordinatorState(joints=snap, t_now=t_now, dt=0.002) - - -# --------------------------------------------------------------------------- -# Tests -# --------------------------------------------------------------------------- - - -def test_claim_shape(task, joints_29): - claim = task.claim() - assert claim.joints == frozenset(joints_29[:15]) - assert claim.priority == 50 - assert claim.mode == ControlMode.SERVO_POSITION - - -def test_inactive_returns_none(task, joints_29): - state = _state_at(100.0, joints_29) - assert task.compute(state) is None - - -def test_active_zero_cmd_routes_to_balance(task, joints_29, patched_ort): - task.start() - # Decimation=10 → run compute 10 times to force first inference. - state = _state_at(100.0, joints_29) - result = None - for _ in range(10): - result = task.compute(state) - assert result is not None - assert len(result.positions) == 15 - assert patched_ort == ["balance"] - - -def test_nonzero_cmd_routes_to_walk(task, joints_29, patched_ort): - task.start() - task.set_velocity_command(0.5, 0.0, 0.0, t_now=100.0) - state = _state_at(100.0, joints_29) - for _ in range(10): - task.compute(state) - assert patched_ort == ["walk"] - - -def test_decimation_reemits_last_targets(task, joints_29, patched_ort): - """Between inference ticks, the task should repeat the last output.""" - task.start() - state = _state_at(100.0, joints_29) - # First 9 ticks pre-inference: no targets yet. - for _ in range(9): - assert task.compute(state) is None - # 10th tick: inference fires. - first = task.compute(state) - assert first is not None - assert len(patched_ort) == 1 - # Next 9 ticks: no inference, same targets echoed. - for _ in range(9): - echo = task.compute(state) - assert echo is not None - assert echo.positions == first.positions - assert len(patched_ort) == 1 - # 20th tick: second inference. - task.compute(state) - assert len(patched_ort) == 2 - - -def test_velocity_command_timeout(task, joints_29, patched_ort): - task.start() - task.set_velocity_command(0.5, 0.0, 0.0, t_now=100.0) - # Still inside the 1.0s timeout — walk. - state_inside = _state_at(100.5, joints_29) - for _ in range(10): - task.compute(state_inside) - # Past the timeout — command goes to zero → balance. - state_outside = _state_at(102.0, joints_29) - for _ in range(10): - task.compute(state_outside) - assert patched_ort == ["walk", "balance"] - - -def test_projected_gravity_identity_quat(): - g = GrootWBCTask._projected_gravity((1.0, 0.0, 0.0, 0.0)) - np.testing.assert_allclose(g, np.array([0.0, 0.0, -1.0]), atol=1e-6) - - -def test_projected_gravity_roll_90(): - """+90° roll around body-X: body-Y now points world-up, body-Z world-right. - World gravity (0,0,-1) expressed in body frame is (0, -1, 0).""" - s = math.sin(math.pi / 4.0) - c = math.cos(math.pi / 4.0) - g = GrootWBCTask._projected_gravity((c, s, 0.0, 0.0)) - np.testing.assert_allclose(g, np.array([0.0, -1.0, 0.0]), atol=1e-6) - - -def test_projected_gravity_pitch_90(): - """+90° pitch around body-Y: body-X now points world-down, body-Z world-forward. - World gravity (0,0,-1) expressed in body frame is (+1, 0, 0).""" - s = math.sin(math.pi / 4.0) - c = math.cos(math.pi / 4.0) - g = GrootWBCTask._projected_gravity((c, 0.0, s, 0.0)) - np.testing.assert_allclose(g, np.array([1.0, 0.0, 0.0]), atol=1e-6) - - -def test_obs_build_layout(task): - """Verify the 86-dim obs respects the documented slot layout.""" - cmd = np.array([1.0, 0.5, 0.25], dtype=np.float32) - gyro = np.array([0.1, 0.2, 0.3], dtype=np.float32) - gravity = np.array([0.0, 0.0, -1.0], dtype=np.float32) - q = np.zeros(29, dtype=np.float32) - dq = np.ones(29, dtype=np.float32) - obs = task._build_obs(cmd=cmd, gyro=gyro, gravity=gravity, q=q, dq=dq) - assert obs.shape == (86,) - np.testing.assert_allclose(obs[0:3], cmd * np.array([2.0, 2.0, 0.5])) - assert obs[3] == pytest.approx(0.74) - np.testing.assert_array_equal(obs[4:7], np.zeros(3)) - np.testing.assert_allclose(obs[7:10], gyro * 0.5) - np.testing.assert_array_equal(obs[10:13], gravity) - # q - default_29 → legs/waist get nonzero offsets from DEFAULT_15, - # arms (indices 15..28 in DEFAULT_29) are zero, so obs[28:42] == 0. - np.testing.assert_array_equal(obs[28:42], np.zeros(14)) - np.testing.assert_allclose(obs[42:71], dq * 0.05) - np.testing.assert_array_equal(obs[71:86], np.zeros(15)) - - -def test_first_inference_fills_history(task, joints_29, patched_ort): - """First inference should tile current obs across all 6 history slots.""" - task.start() - state = _state_at(100.0, joints_29) - for _ in range(10): - task.compute(state) - # History has 6 identical 86-dim slices. - buf = task._obs_buf[0] - assert buf.shape == (86 * 6,) - slice0 = buf[0:86] - for k in range(1, 6): - np.testing.assert_array_equal(buf[86 * k : 86 * (k + 1)], slice0) - - -def test_start_resets_state(task, joints_29, patched_ort): - task.start() - state = _state_at(100.0, joints_29) - for _ in range(10): - task.compute(state) - assert np.any(task._last_action != 0.0) - assert task._last_targets is not None - - task.stop() - assert task._last_targets is None - - task.start() - # After restart, tick counter is zero, last_action cleared, first-inference flag set. - assert task._tick_count == 0 - np.testing.assert_array_equal(task._last_action, np.zeros(15, dtype=np.float32)) - assert task._first_inference is True - - -def test_on_twist_routes_to_velocity_cmd(task): - msg = MagicMock() - msg.linear.x = 0.7 - msg.linear.y = -0.2 - msg.angular.z = 0.4 - task.on_twist(msg, t_now=12.34) - np.testing.assert_allclose(task._cmd, np.array([0.7, -0.2, 0.4], dtype=np.float32), atol=1e-6) - assert task._last_cmd_time == 12.34 - - -def test_joint_count_validation(patched_ort, stub_adapter, joints_29): - with pytest.raises(ValueError, match="15 joint names"): - GrootWBCTask( - name="bad", - config=GrootWBCTaskConfig( - balance_onnx="/fake/balance.onnx", - walk_onnx="/fake/walk.onnx", - joint_names=joints_29[:10], # wrong size - all_joint_names=joints_29, - ), - adapter=stub_adapter, - ) - with pytest.raises(ValueError, match="29 all_joint_names"): - GrootWBCTask( - name="bad", - config=GrootWBCTaskConfig( - balance_onnx="/fake/balance.onnx", - walk_onnx="/fake/walk.onnx", - joint_names=joints_29[:15], - all_joint_names=joints_29[:20], # wrong size - ), - adapter=stub_adapter, - ) - - -# --------------------------------------------------------------------------- -# Arming / dry-run state machine -# --------------------------------------------------------------------------- - - -def test_unarmed_holds_current_pose(unarmed_task, joints_29, patched_ort): - """Active but unarmed → compute() echoes current joint positions - every tick. Downstream PD with q_tgt == q_actual → damping only.""" - unarmed_task.start() - snap = JointStateSnapshot( - joint_positions={n: 0.0 for n in joints_29}, - joint_velocities={n: 0.0 for n in joints_29}, - joint_efforts={n: 0.0 for n in joints_29}, - timestamp=100.0, - ) - # Set some non-zero current positions for the 15 claimed joints. - for i, n in enumerate(joints_29[:15]): - snap.joint_positions[n] = 0.1 * (i + 1) - state = CoordinatorState(joints=snap, t_now=100.0, dt=0.002) - for _ in range(30): - out = unarmed_task.compute(state) - assert out is not None - # No inference while unarmed. - assert patched_ort == [] - # Output tracks current pose exactly. - np.testing.assert_allclose(out.positions, [0.1 * (i + 1) for i in range(15)], atol=1e-6) - - -def test_arm_no_ramp_goes_straight_to_policy(unarmed_task, joints_29, patched_ort): - """arm(0.0) → immediately armed → policy runs on the next decimation tick.""" - unarmed_task.start() - unarmed_task.arm(ramp_seconds=0.0) - state = _state_at(100.0, joints_29) - # First compute after arm(): snapshots ramp_start, flips armed=True (ramp=0). - unarmed_task.compute(state) - assert unarmed_task._armed - # 9 more ticks to hit decimation threshold (10th is inference). - for _ in range(9): - unarmed_task.compute(state) - assert patched_ort == ["balance"] - - -def test_arm_with_ramp_lerps_over_duration(unarmed_task, joints_29, patched_ort): - """arm(1.0) → lerp from current pose to default_15 over 1 second.""" - unarmed_task.start() - unarmed_task.arm(ramp_seconds=1.0) - # First tick: snapshot ramp_start (all zeros). - state0 = _state_at(0.0, joints_29) - out0 = unarmed_task.compute(state0) - assert out0 is not None - assert unarmed_task._arming - # alpha=0 → output == ramp_start (all zeros here). - np.testing.assert_allclose(out0.positions, [0.0] * 15, atol=1e-6) - # Halfway through: alpha=0.5. - state_mid = _state_at(0.5, joints_29) - out_mid = unarmed_task.compute(state_mid) - default_15 = list(groot_wbc_task._DEFAULT_POSITIONS_29[:15]) - expected_mid = [0.5 * d for d in default_15] - np.testing.assert_allclose(out_mid.positions, expected_mid, atol=1e-6) - # End: alpha=1 → armed flips, output == default_15. - state_end = _state_at(1.0, joints_29) - unarmed_task.compute(state_end) - assert unarmed_task._armed - assert not unarmed_task._arming - # Policy has NOT run yet — ramp completion doesn't trigger inference. - assert patched_ort == [] - - -def test_dry_run_suppresses_output_but_runs_inference(task, joints_29, patched_ort): - """Dry-run: policy still computes (obs history stays hot), but - compute() returns None so the adapter sees no command.""" - task.start() # fixture has auto_arm=True, so armed immediately - task.set_dry_run(True) - state = _state_at(100.0, joints_29) - # 10 ticks → first inference fires under the hood, but output is None. - for _ in range(10): - out = task.compute(state) - assert out is None - # Policy DID run — obs buffer is hot. - assert patched_ort == ["balance"] - - -def test_dry_run_toggle_off_resumes_output(task, joints_29, patched_ort): - """Flipping dry_run from True → False resumes normal output.""" - task.start() - task.set_dry_run(True) - state = _state_at(100.0, joints_29) - for _ in range(10): - task.compute(state) - assert patched_ort == ["balance"] # ran during dry-run - task.set_dry_run(False) - # Next inference tick: output is non-None. - for _ in range(10): - out = task.compute(state) - assert out is not None - assert len(out.positions) == 15 - - -def test_disarm_returns_to_hold_pose(unarmed_task, joints_29, patched_ort): - """Disarm after policy has run → compute() falls back to echoing pose.""" - unarmed_task.start() - unarmed_task.arm(ramp_seconds=0.0) - state = _state_at(100.0, joints_29) - for _ in range(10): - unarmed_task.compute(state) - assert patched_ort == ["balance"] - assert unarmed_task._armed - - unarmed_task.disarm() - assert not unarmed_task._armed - # Policy should NOT run again. - for _ in range(30): - unarmed_task.compute(state) - assert patched_ort == ["balance"] # still just one call diff --git a/dimos/core/global_config.py b/dimos/core/global_config.py index 1555feac8c..cefd3f1ebc 100644 --- a/dimos/core/global_config.py +++ b/dimos/core/global_config.py @@ -52,7 +52,6 @@ class GlobalConfig(BaseSettings): nerf_speed: float = 1.0 planner_robot_speed: float | None = None mcp_port: int = 9990 - viser_port: int = 8082 dtop: bool = False obstacle_avoidance: bool = True detection_model: VlModelName = "moondream" diff --git a/dimos/robot/unitree/g1/system_prompt.py b/dimos/robot/unitree/g1/system_prompt.py index b9060d28a2..09acda3c16 100644 --- a/dimos/robot/unitree/g1/system_prompt.py +++ b/dimos/robot/unitree/g1/system_prompt.py @@ -53,11 +53,6 @@ - Tag important locations with `tag_location` so you can return to them later. - During `start_exploration`, avoid calling other skills except `stop_movement`. -## Object database (perception2) -- `list_objects` returns every object you've detected so far with its world position and observation count. Call this when asked "what have you seen?" or before deciding where to go. -- `find_object("query")` does a name search across the database — e.g. `find_object("flag")` returns matching entries. -- `goto_object("name")` sets a navigation goal at the object's center. The name must match what `list_objects` shows. - # BEHAVIOR Be proactive. Infer reasonable actions from ambiguous requests. Inform the user of your assumption. """ From 3c1aacc2c3d397fa604c2284cfa9be7322a36bf4 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 00:56:50 +0200 Subject: [PATCH 09/23] chore(g1-wbc): drop __init__.py files, match repo namespace-package convention --- dimos/hardware/whole_body/__init__.py | 15 --------------- dimos/hardware/whole_body/mujoco/__init__.py | 0 dimos/hardware/whole_body/mujoco/g1/__init__.py | 0 dimos/hardware/whole_body/unitree/__init__.py | 15 --------------- dimos/hardware/whole_body/unitree/g1/__init__.py | 0 5 files changed, 30 deletions(-) delete mode 100644 dimos/hardware/whole_body/__init__.py delete mode 100644 dimos/hardware/whole_body/mujoco/__init__.py delete mode 100644 dimos/hardware/whole_body/mujoco/g1/__init__.py delete mode 100644 dimos/hardware/whole_body/unitree/__init__.py delete mode 100644 dimos/hardware/whole_body/unitree/g1/__init__.py diff --git a/dimos/hardware/whole_body/__init__.py b/dimos/hardware/whole_body/__init__.py deleted file mode 100644 index 8e8e0ccabd..0000000000 --- a/dimos/hardware/whole_body/__init__.py +++ /dev/null @@ -1,15 +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. - -"""Quadruped hardware adapters for joint-level control.""" diff --git a/dimos/hardware/whole_body/mujoco/__init__.py b/dimos/hardware/whole_body/mujoco/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/dimos/hardware/whole_body/mujoco/g1/__init__.py b/dimos/hardware/whole_body/mujoco/g1/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/dimos/hardware/whole_body/unitree/__init__.py b/dimos/hardware/whole_body/unitree/__init__.py deleted file mode 100644 index 5bfe622b00..0000000000 --- a/dimos/hardware/whole_body/unitree/__init__.py +++ /dev/null @@ -1,15 +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. - -"""Unitree quadruped adapters.""" diff --git a/dimos/hardware/whole_body/unitree/g1/__init__.py b/dimos/hardware/whole_body/unitree/g1/__init__.py deleted file mode 100644 index e69de29bb2..0000000000 From 88255494bf16e83a76d185f1358beb52b65f766a Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 01:52:08 +0200 Subject: [PATCH 10/23] chore(g1-wbc): drop simulation/mujoco/model.py changes (unrelated to PR) --- dimos/simulation/mujoco/model.py | 19 +------------------ 1 file changed, 1 insertion(+), 18 deletions(-) diff --git a/dimos/simulation/mujoco/model.py b/dimos/simulation/mujoco/model.py index ac1713f090..bc309b7307 100644 --- a/dimos/simulation/mujoco/model.py +++ b/dimos/simulation/mujoco/model.py @@ -42,9 +42,6 @@ def get_assets() -> dict[str, bytes]: # Assets used from https://sketchfab.com/3d-models/mersus-office-8714be387bcd406898b2615f7dae3a47 # Created by Ryan Cassidy and Coleman Costello mjx_env.update_assets(assets, data_dir, "*.xml") - mjx_env.update_assets( - assets, data_dir, "*.obj" - ) # top-level scene meshes (e.g. dimos_office.obj) mjx_env.update_assets(assets, data_dir / "scene_office1/textures", "*.png") mjx_env.update_assets(assets, data_dir / "scene_office1/office_split", "*.obj") mjx_env.update_assets(assets, mjx_env.MENAGERIE_PATH / "unitree_go1" / "assets") @@ -59,19 +56,8 @@ def get_assets() -> dict[str, bytes]: def load_model( - input_device: InputController, - robot: str, - scene_xml: str, - skip_controller: bool = False, + input_device: InputController, robot: str, scene_xml: str ) -> tuple[mujoco.MjModel, mujoco.MjData]: - """Load a MuJoCo model + data for ``robot`` inside ``scene_xml``. - - When ``skip_controller=True``, the baked-in ONNX locomotion policy is - NOT installed as the MuJoCo control callback. Used by low-level - passthrough mode where an external caller (e.g. the dimos - ControlCoordinator via shared memory) drives ``data.ctrl`` each - tick. - """ mujoco.set_mjcb_control(None) xml_string = get_model_xml(robot, scene_xml) @@ -90,9 +76,6 @@ def load_model( n_substeps = round(ctrl_dt / sim_dt) model.opt.timestep = sim_dt - if skip_controller: - return model, data - params = { "policy_path": (_get_data_dir() / f"{robot}_policy.onnx").as_posix(), "default_angles": np.array(model.keyframe("home").qpos[7:]), From 62a1110d8c50466c56ff59130c76e81fbff71c0b Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 02:04:34 +0200 Subject: [PATCH 11/23] chore(g1-wbc): drop unused make_quadruped_joints + GRIPPER enum (carry-over from old quadruped branch) --- dimos/control/components.py | 35 ----------------------------------- 1 file changed, 35 deletions(-) diff --git a/dimos/control/components.py b/dimos/control/components.py index 09370ca392..68cd671918 100644 --- a/dimos/control/components.py +++ b/dimos/control/components.py @@ -39,7 +39,6 @@ def split_joint_name(joint_name: str) -> tuple[str, str]: class HardwareType(Enum): MANIPULATOR = "manipulator" BASE = "base" - GRIPPER = "gripper" WHOLE_BODY = "whole_body" @@ -151,39 +150,6 @@ def make_twist_base_joints( return [f"{hardware_id}/{s}" for s in suffixes] -_QUADRUPED_LEG_JOINTS = [ - "FR_0", - "FR_1", - "FR_2", - "FL_0", - "FL_1", - "FL_2", - "RR_0", - "RR_1", - "RR_2", - "RL_0", - "RL_1", - "RL_2", -] - - -def make_quadruped_joints(hardware_id: HardwareId) -> list[JointName]: - """Create joint names for a 12-DOF quadruped. - - Uses standard leg naming: FR/FL/RR/RL with 3 joints each - (hip, thigh, calf). Slash-separated to match - ``split_joint_name`` (consistent with ``make_humanoid_joints`` - and ``make_twist_base_joints``). - - Args: - hardware_id: The hardware identifier (e.g., "go2") - - Returns: - List of 12 joint names like ["go2/FR_0", "go2/FR_1", ..., "go2/RL_2"] - """ - return [f"{hardware_id}/{j}" for j in _QUADRUPED_LEG_JOINTS] - - _HUMANOID_29DOF_JOINTS = [ # Left leg (0-5) "left_hip_pitch", @@ -247,7 +213,6 @@ def make_humanoid_joints(hardware_id: HardwareId) -> list[JointName]: "make_gripper_joints", "make_humanoid_joints", "make_joints", - "make_quadruped_joints", "make_twist_base_joints", "split_joint_name", ] From 2d2ba1d4f4c2be5fe629267a468a0156505a2ec9 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 04:33:17 +0200 Subject: [PATCH 12/23] chore(g1-wbc): strip unrelated leftovers (lidar scene_option, get_camera_pose, _publish_tf refactor, spec.py docstring expansion) --- dimos/hardware/whole_body/spec.py | 79 +++---------------- dimos/simulation/engines/mujoco_engine.py | 45 ++--------- dimos/simulation/engines/mujoco_sim_module.py | 15 ++-- 3 files changed, 26 insertions(+), 113 deletions(-) diff --git a/dimos/hardware/whole_body/spec.py b/dimos/hardware/whole_body/spec.py index 3535f35ff0..f7dc9167f3 100644 --- a/dimos/hardware/whole_body/spec.py +++ b/dimos/hardware/whole_body/spec.py @@ -12,14 +12,7 @@ # See the License for the specific language governing permissions and # limitations under the License. -"""WholeBodyAdapter protocol for joint-level motor control. - -Lightweight protocol for robots that expose per-motor -position/velocity/torque control (as opposed to TwistBaseAdapter which -only exposes velocity commands). - -Supports any number of motors — quadrupeds (12 DOF), humanoids (29 DOF), etc. -""" +"""WholeBodyAdapter protocol for joint-level (q/dq/kp/kd/tau) motor control.""" from __future__ import annotations @@ -29,7 +22,7 @@ if TYPE_CHECKING: from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped -# Sentinel values from Unitree SDK — used to signal "no command" for a DOF. +# Unitree SDK sentinels meaning "no command" for that DOF. POS_STOP: float = 2.146e9 VEL_STOP: float = 16000.0 @@ -85,67 +78,19 @@ class WholeBodyConfig: @runtime_checkable class WholeBodyAdapter(Protocol): - """Protocol for joint-level whole-body motor IO. - - Implement this per vendor SDK. All methods use SI units: - - Position: radians - - Velocity: rad/s - - Torque: Nm - - Force: N - """ - - # --- Connection --- - - def connect(self) -> bool: - """Connect to hardware. Returns True on success.""" - ... - - def disconnect(self) -> None: - """Disconnect from hardware.""" - ... - - def is_connected(self) -> bool: - """Check if connected.""" - ... - - # --- State Reading --- - - def read_motor_states(self) -> list[MotorState]: - """Read motor states for all joints.""" - ... - - def has_motor_states(self) -> bool: - """Whether ``read_motor_states`` will return live data. - - Real-hardware adapters return False until the first DDS state - message arrives; sim adapters that always have ground truth - can hardcode True. ConnectedWholeBody uses this to defer - publishing joint_state until the adapter is producing real - feedback, avoiding a leading zero-quat pose. - """ - ... - - def read_imu(self) -> IMUState: - """Read IMU state.""" - ... - + """Joint-level whole-body motor IO. SI units (rad, rad/s, Nm).""" + + def connect(self) -> bool: ... + def disconnect(self) -> None: ... + def is_connected(self) -> bool: ... + def read_motor_states(self) -> list[MotorState]: ... + def has_motor_states(self) -> bool: ... + def read_imu(self) -> IMUState: ... def read_odom(self) -> PoseStamped | None: - """Read latest base pose in world frame, if the adapter has one. - - Sim adapters return the simulator's ground-truth base pose. - Real-hardware adapters return None unless they wire up an - onboard estimator (IMU + leg kinematics fusion, DDS odom topic, - ROS /odom subscription, etc.). The coordinator publishes - ``odom: Out[PoseStamped]`` only when this returns a value, so a - ``None`` return is a quiet no-op rather than a default zero pose. - """ + # Default: no base pose available. Sim/estimator adapters override. return None - # --- Control --- - - def write_motor_commands(self, commands: list[MotorCommand]) -> bool: - """Write motor commands for all joints. Returns success.""" - ... + def write_motor_commands(self, commands: list[MotorCommand]) -> bool: ... __all__ = [ diff --git a/dimos/simulation/engines/mujoco_engine.py b/dimos/simulation/engines/mujoco_engine.py index d16f218c20..bd244af9f2 100644 --- a/dimos/simulation/engines/mujoco_engine.py +++ b/dimos/simulation/engines/mujoco_engine.py @@ -48,13 +48,6 @@ class CameraConfig: width: int = 640 height: int = 480 fps: float = 15.0 - # Per-camera ``mjvOption`` applied during ``update_scene``. Lets a - # caller render the same scene through different geom-group masks - # — e.g. lidar cameras that should only see the static scene mesh - # (group 3) and ignore the robot (groups 0-2), so the lidar - # pointcloud doesn't pick up the robot's own hands/torso/legs as - # phantom obstacles. ``None`` keeps MuJoCo's default (all groups). - scene_option: mujoco.MjvOption | None = None @dataclass @@ -266,21 +259,11 @@ def _render_cameras(self, now: float, cam_renderers: dict[str, _CameraRendererSt continue state.last_render_time = now - scene_option = state.cfg.scene_option - if scene_option is not None: - state.rgb_renderer.update_scene( - self._data, camera=state.cam_id, scene_option=scene_option - ) - rgb = state.rgb_renderer.render().copy() - state.depth_renderer.update_scene( - self._data, camera=state.cam_id, scene_option=scene_option - ) - depth = state.depth_renderer.render().copy() - else: - state.rgb_renderer.update_scene(self._data, camera=state.cam_id) - rgb = state.rgb_renderer.render().copy() - state.depth_renderer.update_scene(self._data, camera=state.cam_id) - depth = state.depth_renderer.render().copy() + state.rgb_renderer.update_scene(self._data, camera=state.cam_id) + rgb = state.rgb_renderer.render().copy() + + state.depth_renderer.update_scene(self._data, camera=state.cam_id) + depth = state.depth_renderer.render().copy() frame = CameraFrame( rgb=rgb, @@ -483,24 +466,6 @@ 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[np.ndarray, np.ndarray] | None: - """World pose of a named camera, regardless of whether it renders. - - Returns ``(cam_pos (3,), cam_mat (3, 3))`` from the latest physics - step. ``cam_xpos`` / ``cam_xmat`` are populated for every MJCF - camera at every step, so this works even when the camera isn't in - the ``cameras`` list passed to MujocoEngine — useful for publishing - TF for cameras that exist in the model purely as mount points - (e.g. head_color when only the lidar render is consumed). - """ - 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().reshape(3, 3), - ) - __all__ = [ "CameraConfig", diff --git a/dimos/simulation/engines/mujoco_sim_module.py b/dimos/simulation/engines/mujoco_sim_module.py index 617a99fbd9..bcca08a1ed 100644 --- a/dimos/simulation/engines/mujoco_sim_module.py +++ b/dimos/simulation/engines/mujoco_sim_module.py @@ -53,6 +53,7 @@ from dimos.msgs.sensor_msgs.PointCloud2 import PointCloud2 from dimos.simulation.engines.mujoco_engine import ( CameraConfig, + CameraFrame, MujocoEngine, ) from dimos.simulation.engines.mujoco_shm import ( @@ -580,7 +581,7 @@ def _publish_loop(self) -> None: ) self.depth_image.publish(depth_img) - self._publish_tf(ts, frame.cam_pos, frame.cam_mat) + self._publish_tf(ts, frame) published_count += 1 if published_count == 1: @@ -613,14 +614,16 @@ def _publish_camera_info(self) -> None: self.camera_info.publish(info) self.depth_camera_info.publish(info) - def _publish_tf(self, ts: float, cam_pos: np.ndarray, cam_mat: np.ndarray) -> None: - mj_rot = R.from_matrix(cam_mat.reshape(3, 3)) + def _publish_tf(self, ts: float, frame: CameraFrame | None) -> None: + if frame is None: + return + mj_rot = R.from_matrix(frame.cam_mat.reshape(3, 3)) optical_rot = mj_rot * _RX180 q = optical_rot.as_quat() # xyzw pos = Vector3( - float(cam_pos[0]), - float(cam_pos[1]), - float(cam_pos[2]), + float(frame.cam_pos[0]), + float(frame.cam_pos[1]), + float(frame.cam_pos[2]), ) rot = Quaternion(float(q[0]), float(q[1]), float(q[2]), float(q[3])) self.tf.publish( From fef946058c419857521a83c0a2cd79bcbf4042b3 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 01:31:13 -0700 Subject: [PATCH 13/23] fix(g1-wbc): passive lowstate sub + restore arm/dry_run wiring MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit The DDS callback registered via ChannelSubscriber.Init(handler, 10) doesn't fire reliably on macOS, so the adapter timed out waiting for the first LowState to capture mode_machine. Switch to passive-mode Init(None, 0) and Read() per tick. mode_machine is now hardcoded to the static value for the 29-DOF G1 instead of read-back-then-echoed. Also adds has_motor_states() to satisfy the post-refactor WholeBodyAdapter Protocol, makes _release_sport_mode null-tolerant (CheckMode returns (status, None) once nothing is active), drops the now-unused _on_low_state callback. WebsocketVisModule: restore the arm / disarm / set_dry_run socket.io handlers and the matching activate / dry_run Out[Bool] ports that an earlier cleanup pass dropped — the dashboard buttons now publish on the LCM topics the coordinator already subscribes to. TransportWholeBodyAdapter: trivial Protocol fix — implement read_odom returning None so isinstance(adapter, WholeBodyAdapter) passes the runtime_checkable type check in ControlCoordinator._setup_hardware. --- .../hardware/whole_body/transport/adapter.py | 7 +++ .../hardware/whole_body/unitree/g1/adapter.py | 56 +++++++++++-------- .../web/websocket_vis/websocket_vis_module.py | 40 +++++++++++++ 3 files changed, 80 insertions(+), 23 deletions(-) diff --git a/dimos/hardware/whole_body/transport/adapter.py b/dimos/hardware/whole_body/transport/adapter.py index 8950803bb3..a8184d5839 100644 --- a/dimos/hardware/whole_body/transport/adapter.py +++ b/dimos/hardware/whole_body/transport/adapter.py @@ -33,6 +33,7 @@ if TYPE_CHECKING: from dimos.hardware.whole_body.registry import WholeBodyAdapterRegistry + from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped logger = setup_logger() @@ -128,6 +129,12 @@ def read_imu(self) -> IMUState: return IMUState() return self._latest_imu + def read_odom(self) -> PoseStamped | None: + # No native odom on this transport bridge — publish odom separately + # if a base estimator is available. Returning None satisfies the + # WholeBodyAdapter Protocol's runtime_checkable isinstance check. + return None + def write_motor_commands(self, commands: list[MotorCommand]) -> bool: if self._motor_command_transport is None: logger.warning("write_motor_commands called before connect()") diff --git a/dimos/hardware/whole_body/unitree/g1/adapter.py b/dimos/hardware/whole_body/unitree/g1/adapter.py index 29462d1536..934265300d 100644 --- a/dimos/hardware/whole_body/unitree/g1/adapter.py +++ b/dimos/hardware/whole_body/unitree/g1/adapter.py @@ -130,12 +130,22 @@ def connect(self) -> bool: self._publisher = ChannelPublisher("rt/lowcmd", LowCmd_) self._publisher.Init() + # Passive subscriber — Read() per tick, no callback. Avoids + # the macOS cyclonedds callback-not-firing footgun that bit + # us when this was Init(self._on_low_state, 10). self._subscriber = ChannelSubscriber("rt/lowstate", LowState_) - self._subscriber.Init(self._on_low_state, 10) - - # 3. Initialise LowCmd with safe defaults + self._subscriber.Init(None, 0) + + # 3. Initialise LowCmd with safe defaults. ``mode_machine`` + # is hardcoded to 5 (the unitree-legged-const value for the + # 29-DOF G1). Earlier the adapter blocked here waiting for a + # first LowState to read it back; the macOS cyclonedds + # callback never fires reliably for that, and the value is + # static for this hardware variant — so we just set it. self._low_cmd = unitree_hg_msg_dds__LowCmd_() self._low_cmd.mode_pr = 0 # PR mode (Pitch/Roll) + self._mode_machine = 5 + self._low_cmd.mode_machine = self._mode_machine for i in range(_NUM_MOTOR_SLOTS): self._low_cmd.motor_cmd[i].mode = 0x01 # Enable self._low_cmd.motor_cmd[i].q = POS_STOP @@ -150,17 +160,6 @@ def connect(self) -> bool: logger.info("Releasing sport mode...") self._release_sport_mode() - # 5. Wait for first LowState to get mode_machine - logger.info("Waiting for first LowState to capture mode_machine...") - deadline = time.time() + 10.0 - while self._mode_machine is None and time.time() < deadline: - time.sleep(0.1) - - if self._mode_machine is None: - logger.error("Timed out waiting for LowState — mode_machine not captured") - self._connected = False - return False - self._connected = True logger.info(f"G1 low-level adapter connected (mode_machine={self._mode_machine})") return True @@ -187,8 +186,26 @@ def is_connected(self) -> bool: # State Reading # ========================================================================= + def has_motor_states(self) -> bool: + """True once we've received at least one LowState frame.""" + self._poll_low_state() + return self._low_state is not None + + def _poll_low_state(self) -> None: + """Drain any pending LowState samples into ``self._low_state``. + + Passive-subscriber pattern: ``Read()`` per tick. None means no + fresh sample (treat as drop / keep last value). + """ + if self._subscriber is None: + return + sample = self._subscriber.Read() + if sample is not None: + self._low_state = sample + def read_motor_states(self) -> list[MotorState]: """Read motor states for all 29 joints.""" + self._poll_low_state() with self._lock: if self._low_state is None: return [MotorState()] * _NUM_MOTORS @@ -203,6 +220,7 @@ def read_motor_states(self) -> list[MotorState]: def read_imu(self) -> IMUState: """Read IMU state.""" + self._poll_low_state() with self._lock: if self._low_state is None: return IMUState() @@ -264,14 +282,6 @@ def write_motor_commands(self, commands: list[MotorCommand]) -> bool: # Internal # ========================================================================= - def _on_low_state(self, msg: object) -> None: - """DDS callback for rt/lowstate.""" - with self._lock: - self._low_state = msg - # Capture mode_machine from first LowState - if self._mode_machine is None: - self._mode_machine = msg.mode_machine # type: ignore[attr-defined] - def _release_sport_mode(self) -> None: """Exit sport mode so that low-level commands are accepted. @@ -286,7 +296,7 @@ def _release_sport_mode(self) -> None: msc.Init() _status, result = msc.CheckMode() - while result["name"]: + while result and result.get("name"): msc.ReleaseMode() _status, result = msc.CheckMode() time.sleep(1) diff --git a/dimos/web/websocket_vis/websocket_vis_module.py b/dimos/web/websocket_vis/websocket_vis_module.py index 3d6b3df11c..70d2896132 100644 --- a/dimos/web/websocket_vis/websocket_vis_module.py +++ b/dimos/web/websocket_vis/websocket_vis_module.py @@ -59,6 +59,7 @@ from dimos.msgs.geometry_msgs.Vector3 import Vector3 from dimos.msgs.nav_msgs.OccupancyGrid import OccupancyGrid from dimos.msgs.nav_msgs.Path import Path +from dimos.msgs.std_msgs.Bool import Bool as DimosBool from dimos.utils.logging_config import setup_logger from .optimized_costmap import OptimizedCostmapEncoder @@ -107,6 +108,13 @@ class WebsocketVisModule(Module): stop_explore_cmd: Out[Bool] cmd_vel: Out[Twist] movecmd_stamped: Out[TwistStamped] + # Arming / dry-run for locomotion-policy tasks (e.g. GrootWBCTask). + # Uses dimos.msgs.std_msgs.Bool to match the coordinator's + # ``activate`` / ``dry_run`` In[Bool] ports, rather than + # dimos_lcm.std_msgs.Bool used by ``explore_cmd`` — the LCM wire + # format is identical; what matters for autoconnect is type parity. + activate: Out[DimosBool] + dry_run: Out[DimosBool] def __init__(self, **kwargs: Any) -> None: """Initialize the WebSocket visualization module. @@ -330,6 +338,38 @@ async def clear_gps_goals(sid: str) -> None: await self.sio.emit("gps_travel_goal_points", self.gps_goal_points) logger.info("GPS goal points cleared and updated clients") + @self.sio.event # type: ignore[untyped-decorator] + async def arm(sid: str, data: dict[str, Any] | None = None) -> None: + """Dashboard → arm the locomotion policy (with ramp).""" + if self.activate and self.activate.transport: + logger.info("Dashboard requested arm") + self.activate.publish(DimosBool(data=True)) + else: + logger.warning("arm requested but activate transport is not configured") + + @self.sio.event # type: ignore[untyped-decorator] + async def disarm(sid: str, data: dict[str, Any] | None = None) -> None: + """Dashboard → disarm; task falls back to hold-current-pose.""" + if self.activate and self.activate.transport: + logger.info("Dashboard requested disarm") + self.activate.publish(DimosBool(data=False)) + else: + logger.warning("disarm requested but activate transport is not configured") + + @self.sio.event # type: ignore[untyped-decorator] + async def set_dry_run(sid: str, data: dict[str, Any]) -> None: + """Dashboard → toggle dry-run on the locomotion policy. + + Payload: ``{"enabled": bool}``. Task still computes but + coordinator sends nothing to the adapter when enabled. + """ + if self.dry_run and self.dry_run.transport: + enabled = bool(data.get("enabled", False)) + logger.info(f"Dashboard set dry_run = {enabled}") + self.dry_run.publish(DimosBool(data=enabled)) + else: + logger.warning("set_dry_run requested but dry_run transport is not configured") + @self.sio.event # type: ignore[untyped-decorator] async def move_command(sid: str, data: dict[str, Any]) -> None: # Publish Twist if transport is configured From a400d26adea139a1ed31a8031c68ea090ef7c3ef Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 01:38:45 -0700 Subject: [PATCH 14/23] chore(g1-wbc): restore unrelated files accidentally swept into PR The earlier cleanup pass over-deleted: openarm manipulator support, the dimos/utils/workspace.py module, the audio STT node_whisper edits, CI configs, README, command-center package-lock churn, and two go2 LFS DBs. None of those are part of the GR00T WBC story. Restore each to origin/dev's content. Drop one path that was added on this branch but doesn't exist on dev (api/requirements.txt). PR diff is now 24 files / +2623 / -210, all GR00T-WBC-relevant. --- .codecov.yml | 6 + .github/workflows/ci.yml | 26 +- README.md | 9 +- data/.lfs/go2_hongkong_office.db.tar.gz | 3 + data/.lfs/go2_short.db.tar.gz | 3 + data/.lfs/openarm_description.tar.gz | 3 + dimos/core/global_config.py | 2 +- .../hardware/manipulators/openarm/adapter.py | 433 +++++++++ dimos/hardware/manipulators/openarm/driver.py | 347 ++++++++ .../manipulators/openarm/test_driver.py | 270 ++++++ dimos/robot/catalog/openarm.py | 120 +++ .../robot/manipulators/openarm/blueprints.py | 220 +++++ .../openarm/scripts/openarm_can_probe.py | 206 +++++ .../openarm/scripts/openarm_can_up.sh | 36 + .../openarm/scripts/openarm_set_mit_mode.py | 140 +++ dimos/stream/audio/stt/node_whisper.py | 46 +- dimos/utils/workspace.py | 314 +++++++ .../package-lock.json | 835 +++++++----------- .../web/command-center-extension/package.json | 2 +- dimos/web/dimos_interface/api/README.md | 5 +- .../web/dimos_interface/api/requirements.txt | 7 - .../manipulation/openarm_integration.md | 387 ++++++++ docs/requirements.md | 17 +- 23 files changed, 2884 insertions(+), 553 deletions(-) create mode 100644 .codecov.yml create mode 100644 data/.lfs/go2_hongkong_office.db.tar.gz create mode 100644 data/.lfs/go2_short.db.tar.gz create mode 100644 data/.lfs/openarm_description.tar.gz create mode 100644 dimos/hardware/manipulators/openarm/adapter.py create mode 100644 dimos/hardware/manipulators/openarm/driver.py create mode 100644 dimos/hardware/manipulators/openarm/test_driver.py create mode 100644 dimos/robot/catalog/openarm.py create mode 100644 dimos/robot/manipulators/openarm/blueprints.py create mode 100755 dimos/robot/manipulators/openarm/scripts/openarm_can_probe.py create mode 100755 dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh create mode 100755 dimos/robot/manipulators/openarm/scripts/openarm_set_mit_mode.py create mode 100644 dimos/utils/workspace.py delete mode 100644 dimos/web/dimos_interface/api/requirements.txt create mode 100644 docs/capabilities/manipulation/openarm_integration.md diff --git a/.codecov.yml b/.codecov.yml new file mode 100644 index 0000000000..3d8e566008 --- /dev/null +++ b/.codecov.yml @@ -0,0 +1,6 @@ +codecov: + branch: dev + +comment: + require_head: false + require_base: false diff --git a/.github/workflows/ci.yml b/.github/workflows/ci.yml index 9d7b8caf8a..6f7be26169 100644 --- a/.github/workflows/ci.yml +++ b/.github/workflows/ci.yml @@ -12,6 +12,7 @@ on: permissions: contents: read packages: read + id-token: write jobs: ci-complete: @@ -43,26 +44,27 @@ jobs: find .venv/lib/*/site-packages/pydrake -name '*.pyi' -delete 2>/dev/null || true - name: Run tests - if: github.event_name != 'push' run: | - /entrypoint.sh bash -c "source .venv/bin/activate && pytest --durations=0 -m 'not (tool or mujoco)'" - - - name: Run tests with coverage - if: github.event_name == 'push' - run: | - /entrypoint.sh bash -c "source .venv/bin/activate && _DIMOS_COV=1 coverage run -m pytest --durations=0 -m 'not (tool or mujoco)' && coverage combine && coverage html && coverage report" + /entrypoint.sh bash -c "source .venv/bin/activate && _DIMOS_COV=1 coverage run -m pytest --junitxml=junit.xml --durations=0 -m 'not (tool or mujoco)' && coverage combine && coverage xml" - name: Run mypy if: ${{ !cancelled() }} run: | /entrypoint.sh bash -c "source .venv/bin/activate && MYPYPATH=/opt/ros/humble/lib/python3.10/site-packages mypy dimos" - - name: Upload coverage report - if: github.event_name == 'push' && !cancelled() - uses: actions/upload-artifact@v5 + - name: Upload coverage + uses: codecov/codecov-action@v6 + with: + disable_search: true + fail_ci_if_error: true + files: ./coverage.xml + use_oidc: true + - name: Upload test results to Codecov + if: ${{ !cancelled() }} + uses: codecov/codecov-action@v6 with: - name: coverage-report - path: htmlcov/ + report_type: test_results + use_oidc: true - name: Check disk space if: failure() diff --git a/README.md b/README.md index a16c37f795..1c2aaf29d5 100644 --- a/README.md +++ b/README.md @@ -159,7 +159,7 @@ To set up your system dependencies, follow one of these guides: ```bash uv venv --python "3.12" source .venv/bin/activate -uv pip install 'dimos[base,unitree]' +uv pip install 'dimos[unitree]' # Replay a recorded quadruped session (no hardware needed) # NOTE: First run will show a black rerun window while ~75 MB downloads from LFS @@ -167,8 +167,11 @@ dimos --replay run unitree-go2 ``` ```bash -# Install with simulation support -uv pip install 'dimos[base,unitree,sim]' +# Add perception (object detection, VLMs — heavy dependencies, needs to download GBs) +uv pip install 'dimos[unitree,perception]' + +# Add simulation support +uv pip install 'dimos[unitree,sim]' # Run quadruped in MuJoCo simulation dimos --simulation run unitree-go2 diff --git a/data/.lfs/go2_hongkong_office.db.tar.gz b/data/.lfs/go2_hongkong_office.db.tar.gz new file mode 100644 index 0000000000..38696c1484 --- /dev/null +++ b/data/.lfs/go2_hongkong_office.db.tar.gz @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:d9f472bc9b0b8ce86c6253013800cca86e149b0ab5868c79e5072c7e07f2e3a5 +size 770750369 diff --git a/data/.lfs/go2_short.db.tar.gz b/data/.lfs/go2_short.db.tar.gz new file mode 100644 index 0000000000..092c1de2a3 --- /dev/null +++ b/data/.lfs/go2_short.db.tar.gz @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:7c26ca64b9f63d98070a12b364ecea78a44f2040d82020cdd551c81760c8b4d2 +size 77023899 diff --git a/data/.lfs/openarm_description.tar.gz b/data/.lfs/openarm_description.tar.gz new file mode 100644 index 0000000000..54aa76da41 --- /dev/null +++ b/data/.lfs/openarm_description.tar.gz @@ -0,0 +1,3 @@ +version https://git-lfs.github.com/spec/v1 +oid sha256:4da176b6c210b9796bb2ee1a29c15ee9a67578b9ae906eb89a6ec8a44b7f303a +size 70064687 diff --git a/dimos/core/global_config.py b/dimos/core/global_config.py index cefd3f1ebc..b7c5c1bf12 100644 --- a/dimos/core/global_config.py +++ b/dimos/core/global_config.py @@ -34,7 +34,7 @@ class GlobalConfig(BaseSettings): can_port: str | None = None simulation: bool = False replay: bool = False - replay_db: str = "go2_china_office" + replay_db: str = "go2_short" new_memory: bool = False viewer: ViewerBackend = "rerun" n_workers: int = 2 diff --git a/dimos/hardware/manipulators/openarm/adapter.py b/dimos/hardware/manipulators/openarm/adapter.py new file mode 100644 index 0000000000..70554817e4 --- /dev/null +++ b/dimos/hardware/manipulators/openarm/adapter.py @@ -0,0 +1,433 @@ +# 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. + +"""OpenArm ManipulatorAdapter — wraps the Damiao MIT-mode driver. SI units.""" + +from __future__ import annotations + +from pathlib import Path +import time +from typing import TYPE_CHECKING, Any + +import numpy as np + +from dimos.hardware.manipulators.openarm.driver import ( + CTRL_MODE_MIT, + DamiaoMotor, + MotorType, + OpenArmBus, +) +from dimos.hardware.manipulators.spec import ( + ControlMode, + JointLimits, + ManipulatorInfo, +) +from dimos.utils.data import LfsPath + +if TYPE_CHECKING: + from dimos.hardware.manipulators.registry import AdapterRegistry + + +def _socketcan_iface_up(name: str) -> bool: + try: + flags_path = Path("/sys/class/net") / name / "flags" + if not flags_path.exists(): + return False + return (int(flags_path.read_text().strip(), 16) & 0x1) == 0x1 + except OSError: + return False + + +# OpenArm v10 BOM — (send_id, MotorType) per joint, derived from the torque +# column of data/openarm_description/config/arm/v10/joint_limits.yaml. +_OPENARM_V10_ARM_MOTORS: list[tuple[int, MotorType]] = [ + (0x01, MotorType.DM8006), # joint1 + (0x02, MotorType.DM8006), # joint2 + (0x03, MotorType.DM4340), # joint3 + (0x04, MotorType.DM4340), # joint4 + (0x05, MotorType.DM4310), # joint5 + (0x06, MotorType.DM4310), # joint6 + (0x07, MotorType.DM4310), # joint7 +] +# Gripper (motor id 0x08, DM4310) is on the bus but not currently wired up +# through the adapter — see the gripper-write methods which return None/False. + +# Physical joint limits (measured). Joints 1 & 2 are mirrored between sides. +_V10_POS_LOWER_LEFT = [-3.45, -3.30, -1.50, -0.01, -1.50, -0.75, -1.50] +_V10_POS_UPPER_LEFT = [1.35, 0.15, 1.50, 2.40, 1.50, 0.75, 1.50] +_V10_POS_LOWER_RIGHT = [-1.35, -0.15, -1.50, -0.01, -1.50, -0.75, -1.50] +_V10_POS_UPPER_RIGHT = [3.45, 3.30, 1.50, 2.40, 1.50, 0.75, 1.50] +_V10_VEL_MAX = [16.754666, 16.754666, 5.445426, 5.445426, 20.943946, 20.943946, 20.943946] + +# Default MIT gains per joint for POSITION mode. +# kp range is [0, 500], kd range is [0, 5]. +# With gravity compensation enabled, the PD gains only handle transient +# tracking — they don't fight gravity. Lower kp = smoother, less buzz. +# High kd causes high-frequency buzz/grinding from the gearbox. +_DEFAULT_KP = [100.0, 100.0, 80.0, 80.0, 60.0, 60.0, 60.0] +_DEFAULT_KD = [1.5, 1.5, 1.0, 1.0, 0.8, 0.8, 0.8] +_STATE_MAX_AGE_S = 0.1 + + +class OpenArmAdapter: + """7-DOF OpenArm on one SocketCAN bus. side=left|right picks URDF + limits.""" + + # Per-side URDFs for Pinocchio gravity model (LFS-backed) + _URDF_LEFT = LfsPath("openarm_description/urdf/robot/openarm_v10_left.urdf") + _URDF_RIGHT = LfsPath("openarm_description/urdf/robot/openarm_v10_right.urdf") + + def __init__( + self, + address: str = "can0", + dof: int = 7, + *, + side: str = "left", + fd: bool = False, + interface: str = "socketcan", + kp: list[float] | None = None, + kd: list[float] | None = None, + gravity_comp: bool = True, + auto_set_mit_mode: bool = True, + **_: Any, + ) -> None: + if dof != 7: + raise ValueError(f"OpenArmAdapter only supports 7 DOF (got {dof})") + if side not in ("left", "right"): + raise ValueError(f"side must be 'left' or 'right', got {side!r}") + self._address = address + self._dof = dof + self._side = side + self._fd = fd + self._interface = interface + self._kp = list(kp) if kp is not None else list(_DEFAULT_KP) + self._kd = list(kd) if kd is not None else list(_DEFAULT_KD) + if len(self._kp) != dof or len(self._kd) != dof: + raise ValueError("kp/kd must be length 7") + self._gravity_comp = gravity_comp + self._auto_set_mit_mode = auto_set_mit_mode + + self._motors = [DamiaoMotor(sid, mt) for sid, mt in _OPENARM_V10_ARM_MOTORS] + self._bus: OpenArmBus | None = None + self._control_mode: ControlMode = ControlMode.POSITION + self._enabled: bool = False + # Last successful position command — used as q_target for VELOCITY mode + self._last_cmd_q: list[float] | None = None + + # Pinocchio model for gravity compensation (loaded lazily in connect()) + self._pin_model: Any = None + self._pin_data: Any = None + + def connect(self) -> bool: + # Preflight: verify the SocketCAN interface is up before opening the bus. + # Bringing the interface up requires root privileges, so we don't do it + # here — just fail early with a helpful message. + if self._interface == "socketcan" and not _socketcan_iface_up(self._address): + print( + f"ERROR: SocketCAN interface '{self._address}' is not UP.\n" + f" Run: sudo ip link set {self._address} up type can bitrate 1000000\n" + f" (or: sudo ./dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh {self._address})" + ) + return False + + try: + self._bus = OpenArmBus( + channel=self._address, + motors=self._motors, + fd=self._fd, + interface=self._interface, + ) + self._bus.open() + except Exception as e: + print(f"ERROR: OpenArm {self._side}@{self._address} connect failed: {e}") + self._bus = None + return False + + # Ensure every motor is in MIT control mode. The write is idempotent + # (setting CTRL_MODE=MIT when it's already MIT is a no-op), so we + # write unconditionally rather than query-then-write. + if self._auto_set_mit_mode: + try: + for m in self._motors: + self._bus.write_ctrl_mode(m.send_id, CTRL_MODE_MIT) + except Exception as e: + print(f"ERROR: failed to set MIT mode on {self._address}: {e}") + self._bus.close() + self._bus = None + return False + else: + print( + f"OpenArm {self._side}@{self._address}: " + "auto_set_mit_mode disabled — relying on persisted register" + ) + + # Load Pinocchio model for gravity compensation + if self._gravity_comp: + try: + import pinocchio + + urdf = str(self._URDF_LEFT if self._side == "left" else self._URDF_RIGHT) + self._pin_model = pinocchio.buildModelFromUrdf(urdf) + self._pin_data = self._pin_model.createData() + print( + f"OpenArm {self._side}: gravity compensation enabled (nq={self._pin_model.nq})" + ) + except Exception as e: + print(f"WARNING: gravity comp disabled — {e}") + self._pin_model = None + self._pin_data = None + + return True + + def disconnect(self) -> None: + if self._bus is None: + return + try: + self._bus.disable_all() + except Exception: + pass + self._enabled = False + self._bus.close() + self._bus = None + + def is_connected(self) -> bool: + return self._bus is not None + + def get_info(self) -> ManipulatorInfo: + return ManipulatorInfo( + vendor="Enactic", + model=f"OpenArm v10 ({self._side})", + dof=self._dof, + firmware_version=None, + serial_number=None, + ) + + def get_dof(self) -> int: + return self._dof + + def get_limits(self) -> JointLimits: + if self._side == "left": + lower, upper = _V10_POS_LOWER_LEFT, _V10_POS_UPPER_LEFT + else: + lower, upper = _V10_POS_LOWER_RIGHT, _V10_POS_UPPER_RIGHT + return JointLimits( + position_lower=list(lower), + position_upper=list(upper), + velocity_max=list(_V10_VEL_MAX), + ) + + def set_control_mode(self, mode: ControlMode) -> bool: + # OpenArm runs exclusively in Damiao MIT register mode; we emulate + # dimos ControlModes by tuning kp/kd/q/dq/tau on each MIT frame. + # Cartesian/impedance control are outside this adapter's scope. + if mode in ( + ControlMode.POSITION, + ControlMode.SERVO_POSITION, + ControlMode.VELOCITY, + ControlMode.TORQUE, + ): + self._control_mode = mode + return True + return False + + def get_control_mode(self) -> ControlMode: + return self._control_mode + + def _states_or_raise(self) -> list[Any]: + # Raises on missing or stale data so hardware_interface.py can retry + # (init) or skip the tick (steady-state). + if self._bus is None: + raise RuntimeError("OpenArmAdapter not connected") + now = time.monotonic() + states = self._bus.get_states() + for i, s in enumerate(states): + if s is None: + raise RuntimeError(f"motor {i + 1} has no state yet") + if now - s.timestamp > _STATE_MAX_AGE_S: + age_ms = (now - s.timestamp) * 1000 + raise RuntimeError(f"motor {i + 1} state stale ({age_ms:.0f} ms)") + return states + + def read_joint_positions(self) -> list[float]: + return [s.q for s in self._states_or_raise()] + + def read_joint_velocities(self) -> list[float]: + return [s.dq for s in self._states_or_raise()] + + def read_joint_efforts(self) -> list[float]: + return [s.tau for s in self._states_or_raise()] + + def read_state(self) -> dict[str, int]: + if self._bus is None: + return {"state": 0, "mode": 0} + states = self._bus.get_states() + # report the hottest rotor temperature so callers can monitor thermal + # stress with a single scalar + t_rotor = max((s.t_rotor for s in states if s is not None), default=0) + return { + "state": 1 if self._enabled else 0, + "mode": 1, # MIT + "t_rotor_max": int(t_rotor), + } + + def read_error(self) -> tuple[int, str]: + # The Damiao motors don't report a structured error code in the state + # frame; over-temperature / over-torque are detected by the host from + # the normal state fields. Surface a soft thermal warning here. + if self._bus is None: + return 0, "" + states = self._bus.get_states() + t_rotor = max((s.t_rotor for s in states if s is not None), default=0) + if t_rotor >= 85: + return 1, f"rotor over-temperature ({t_rotor}°C)" + return 0, "" + + def _compute_gravity_torques(self, q: list[float]) -> list[float]: + # Pinocchio G(q), clamped to motor torque limits. + if self._pin_model is None or self._pin_data is None: + return [0.0] * self._dof + import pinocchio + + q_arr = np.array(q, dtype=np.float64) + tau_g = pinocchio.computeGeneralizedGravity(self._pin_model, self._pin_data, q_arr) + # Clamp to motor torque limits for safety + limits = [m.limits for m in self._motors] # (p_max, v_max, t_max) + return [float(np.clip(tau_g[i], -lim[2], lim[2])) for i, lim in enumerate(limits)] + + def write_joint_positions( + self, + positions: list[float], + velocity: float = 1.0, + ) -> bool: + if self._bus is None or not self._enabled: + return False + if len(positions) != self._dof: + return False + velocity = max(0.0, min(1.0, velocity)) + # Gravity feedforward: compute tau needed to hold the arm at the + # current configuration. The PD gains handle the rest. Tolerate + # transient state-cache misses (e.g. startup, brief CAN gap) — fall + # back to commanded q with no feedforward instead of crashing. + try: + q_current = self.read_joint_positions() + tau_ff = self._compute_gravity_torques(q_current) + except RuntimeError: + tau_ff = [0.0] * self._dof + commands = [ + (q, 0.0, kp * velocity, kd, tau) + for q, kp, kd, tau in zip(positions, self._kp, self._kd, tau_ff, strict=False) + ] + self._bus.send_mit_many(commands) + self._last_cmd_q = list(positions) + return True + + def write_joint_velocities(self, velocities: list[float]) -> bool: + # MIT velocity tracking: kp=0, send dq directly, anchor q at the + # last-commanded position so the motor doesn't drift. Gravity + # feedforward is still needed — with kp=0 the only restoring force + # is damping, so without tau_ff the arm droops under its own weight. + if self._bus is None or not self._enabled: + return False + if len(velocities) != self._dof: + return False + # Seed anchor from current pose if we don't have a last-commanded one. + # If state isn't ready yet, can't safely anchor velocity tracking → bail. + if self._last_cmd_q is None: + try: + self._last_cmd_q = self.read_joint_positions() + except RuntimeError: + return False + anchor = self._last_cmd_q + try: + q_current = self.read_joint_positions() + tau_ff = self._compute_gravity_torques(q_current) + except RuntimeError: + tau_ff = [0.0] * self._dof + commands = [ + (q_anchor, dq, 0.0, kd, tau) + for q_anchor, dq, kd, tau in zip(anchor, velocities, self._kd, tau_ff, strict=False) + ] + self._bus.send_mit_many(commands) + return True + + def write_stop(self) -> bool: + if self._bus is None: + return False + # Without current positions we can't safely command "hold here" — sending + # any guessed q would torque the arm toward that pose. Bail out instead. + try: + q_now = self.read_joint_positions() + except RuntimeError: + return False + tau_ff = self._compute_gravity_torques(q_now) + commands = [ + (q, 0.0, kp, kd, tau) + for q, kp, kd, tau in zip(q_now, self._kp, self._kd, tau_ff, strict=False) + ] + self._bus.send_mit_many(commands) + self._last_cmd_q = q_now + return True + + def write_enable(self, enable: bool) -> bool: + if self._bus is None: + return False + self._enabled = False + try: + if enable: + self._bus.enable_all() + else: + self._bus.disable_all() + except Exception: + return False + self._enabled = enable + return True + + def read_enabled(self) -> bool: + return self._enabled + + def write_clear_errors(self) -> bool: + # Damiao motors have no separate clear-error command; re-enabling + # after a fault is the recovery path. + if self._bus is None: + return False + self._enabled = False + try: + self._bus.disable_all() + self._bus.enable_all() + except Exception: + return False + self._enabled = True + return True + + def read_cartesian_position(self) -> dict[str, float] | None: + return None + + def write_cartesian_position(self, pose: dict[str, float], velocity: float = 1.0) -> bool: + return False + + def read_gripper_position(self) -> float | None: + return None + + def write_gripper_position(self, position: float) -> bool: + return False + + def read_force_torque(self) -> list[float] | None: + return None + + +# ── Registry hook (required for auto-discovery) ─────────────────── +def register(registry: AdapterRegistry) -> None: + registry.register("openarm", OpenArmAdapter) + + +__all__ = ["OpenArmAdapter", "register"] diff --git a/dimos/hardware/manipulators/openarm/driver.py b/dimos/hardware/manipulators/openarm/driver.py new file mode 100644 index 0000000000..0783bd76ed --- /dev/null +++ b/dimos/hardware/manipulators/openarm/driver.py @@ -0,0 +1,347 @@ +# 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. + +"""Damiao MIT-mode CAN driver for OpenArm. SI units throughout. + +Ported from ``enactic/openarm_can`` (C++). No dimos deps — testable with +``can.Bus(interface="virtual")``. +""" + +from __future__ import annotations + +from dataclasses import dataclass +import enum +import errno +import struct +import threading +import time +from typing import TYPE_CHECKING + +if TYPE_CHECKING: + import can + + +class MotorType(str, enum.Enum): + """Damiao motor types used on OpenArm. Values match the reference library.""" + + DM3507 = "DM3507" + DM4310 = "DM4310" + DM4310_48V = "DM4310_48V" + DM4340 = "DM4340" + DM4340_48V = "DM4340_48V" + DM6006 = "DM6006" + DM8006 = "DM8006" + DM8009 = "DM8009" + DM10010L = "DM10010L" + DM10010 = "DM10010" + DMH3510 = "DMH3510" + DMH6215 = "DMH6215" + DMG6220 = "DMG6220" + + +# (p_max [rad], v_max [rad/s], t_max [Nm]) +_MOTOR_LIMITS: dict[MotorType, tuple[float, float, float]] = { + MotorType.DM3507: (12.5, 50.0, 5.0), + MotorType.DM4310: (12.5, 30.0, 10.0), + MotorType.DM4310_48V: (12.5, 50.0, 10.0), + MotorType.DM4340: (12.5, 8.0, 28.0), + MotorType.DM4340_48V: (12.5, 10.0, 28.0), + MotorType.DM6006: (12.5, 45.0, 20.0), + MotorType.DM8006: (12.5, 45.0, 40.0), + MotorType.DM8009: (12.5, 45.0, 54.0), + MotorType.DM10010L: (12.5, 25.0, 200.0), + MotorType.DM10010: (12.5, 20.0, 200.0), + MotorType.DMH3510: (12.5, 280.0, 1.0), + MotorType.DMH6215: (12.5, 45.0, 10.0), + MotorType.DMG6220: (12.5, 45.0, 10.0), +} + +# MIT gain ranges (protocol-fixed, same for every motor type) +KP_MIN, KP_MAX = 0.0, 500.0 +KD_MIN, KD_MAX = 0.0, 5.0 + +# Broadcast/control CAN IDs +_BROADCAST_ID = 0x7FF +_CMD_ENABLE = 0xFC +_CMD_DISABLE = 0xFD +_RID_CTRL_MODE = 10 +CTRL_MODE_MIT = 1 + + +def _clamp(x: float, lo: float, hi: float) -> float: + if x < lo: + return lo + if x > hi: + return hi + return x + + +def float_to_uint(x: float, lo: float, hi: float, bits: int) -> int: + x = _clamp(x, lo, hi) + return int((x - lo) / (hi - lo) * ((1 << bits) - 1)) + + +def uint_to_float(u: int, lo: float, hi: float, bits: int) -> float: + return u / ((1 << bits) - 1) * (hi - lo) + lo + + +def pack_mit_frame( + motor_type: MotorType, + q: float, + dq: float, + kp: float, + kd: float, + tau: float, +) -> bytes: + p_max, v_max, t_max = _MOTOR_LIMITS[motor_type] + q_u = float_to_uint(q, -p_max, p_max, 16) + dq_u = float_to_uint(dq, -v_max, v_max, 12) + kp_u = float_to_uint(kp, KP_MIN, KP_MAX, 12) + kd_u = float_to_uint(kd, KD_MIN, KD_MAX, 12) + tau_u = float_to_uint(tau, -t_max, t_max, 12) + return bytes( + [ + (q_u >> 8) & 0xFF, + q_u & 0xFF, + (dq_u >> 4) & 0xFF, + ((dq_u & 0xF) << 4) | ((kp_u >> 8) & 0xF), + kp_u & 0xFF, + (kd_u >> 4) & 0xFF, + ((kd_u & 0xF) << 4) | ((tau_u >> 8) & 0xF), + tau_u & 0xFF, + ] + ) + + +@dataclass(frozen=True) +class MotorState: + """Decoded state from a Damiao reply frame.""" + + q: float # rad + dq: float # rad/s + tau: float # Nm + t_mos: int # °C + t_rotor: int # °C + timestamp: float # monotonic seconds when received + + +def parse_state_frame(motor_type: MotorType, data: bytes) -> MotorState | None: + """Decode an 8-byte Damiao state reply. Returns None if too short.""" + if len(data) < 8: + return None + p_max, v_max, t_max = _MOTOR_LIMITS[motor_type] + q_u = (data[1] << 8) | data[2] + dq_u = (data[3] << 4) | (data[4] >> 4) + tau_u = ((data[4] & 0x0F) << 8) | data[5] + return MotorState( + q=uint_to_float(q_u, -p_max, p_max, 16), + dq=uint_to_float(dq_u, -v_max, v_max, 12), + tau=uint_to_float(tau_u, -t_max, t_max, 12), + t_mos=int(data[6]), + t_rotor=int(data[7]), + timestamp=time.monotonic(), + ) + + +def _pack_control_command(cmd: int) -> bytes: + return bytes([0xFF] * 7 + [cmd & 0xFF]) + + +def pack_write_param_frame(send_id: int, rid: int, value_u32: int) -> bytes: + """Broadcast parameter-write frame sent to CAN id 0x7FF.""" + val = struct.pack("> 8) & 0xFF, + 0x55, + rid & 0xFF, + val[0], + val[1], + val[2], + val[3], + ] + ) + + +@dataclass(frozen=True) +class DamiaoMotor: + """One Damiao motor on a CAN bus. recv_id defaults to send_id | 0x10.""" + + send_id: int + motor_type: MotorType + recv_id: int | None = None + + @property + def effective_recv_id(self) -> int: + return self.recv_id if self.recv_id is not None else (self.send_id | 0x10) + + @property + def limits(self) -> tuple[float, float, float]: + return _MOTOR_LIMITS[self.motor_type] + + +class OpenArmBus: + """One SocketCAN bus with a background RX thread caching latest state.""" + + def __init__( + self, + channel: str, + motors: list[DamiaoMotor], + *, + fd: bool = False, + interface: str = "socketcan", + ) -> None: + if not motors: + raise ValueError("OpenArmBus needs at least one motor") + # Enforce unique IDs — silent overlap would make state routing ambiguous. + send_ids = [m.send_id for m in motors] + if len(set(send_ids)) != len(send_ids): + raise ValueError(f"duplicate send_id in {send_ids}") + recv_ids = [m.effective_recv_id for m in motors] + if len(set(recv_ids)) != len(recv_ids): + raise ValueError(f"duplicate recv_id in {recv_ids}") + + self._channel = channel + self._motors = list(motors) + self._fd = fd + self._interface = interface + self._by_recv: dict[int, DamiaoMotor] = {m.effective_recv_id: m for m in motors} + + self._bus: can.BusABC | None = None + self._rx_thread: threading.Thread | None = None + self._rx_stop = threading.Event() + self._state_lock = threading.Lock() + self._states: dict[int, MotorState] = {} + + def open(self) -> None: + """Open the CAN bus and start the background RX thread.""" + if self._bus is not None: + return + import can # local import — python-can is optional + + self._bus = can.Bus(interface=self._interface, channel=self._channel, fd=self._fd) + self._rx_stop.clear() + self._rx_thread = threading.Thread( + target=self._rx_loop, name=f"openarm-rx-{self._channel}", daemon=True + ) + self._rx_thread.start() + + def close(self) -> None: + """Stop the RX thread and close the CAN bus.""" + self._rx_stop.set() + if self._rx_thread is not None: + self._rx_thread.join(timeout=1.0) + self._rx_thread = None + if self._bus is not None: + try: + self._bus.shutdown() + finally: + self._bus = None + + def enable_all(self) -> None: + for m in self._motors: + self._send_raw(m.send_id, _pack_control_command(_CMD_ENABLE)) + + def disable_all(self) -> None: + for m in self._motors: + self._send_raw(m.send_id, _pack_control_command(_CMD_DISABLE)) + + def write_ctrl_mode(self, send_id: int, mode: int = CTRL_MODE_MIT) -> None: + self._send_raw( + _BROADCAST_ID, + pack_write_param_frame(send_id, _RID_CTRL_MODE, mode), + ) + + def send_mit_many( + self, + commands: list[tuple[float, float, float, float, float]], + ) -> None: + """One MIT frame per motor; commands[i] → self.motors[i] = (q, dq, kp, kd, tau).""" + if len(commands) != len(self._motors): + raise ValueError(f"expected {len(self._motors)} commands, got {len(commands)}") + for motor, cmd in zip(self._motors, commands, strict=False): + q, dq, kp, kd, tau = cmd + data = pack_mit_frame(motor.motor_type, q, dq, kp, kd, tau) + self._send_raw(motor.send_id, data) + + def get_state(self, send_id: int) -> MotorState | None: + motor = next((m for m in self._motors if m.send_id == send_id), None) + if motor is None: + return None + with self._state_lock: + return self._states.get(motor.effective_recv_id) + + def get_states(self) -> list[MotorState | None]: + with self._state_lock: + return [self._states.get(m.effective_recv_id) for m in self._motors] + + def _send_raw(self, arbitration_id: int, data: bytes) -> None: + if self._bus is None: + raise RuntimeError("bus not open — call .open() first") + import can + + msg = can.Message( + arbitration_id=arbitration_id, + data=data, + is_extended_id=False, + is_fd=self._fd, + bitrate_switch=self._fd, + ) + # Retry on TX buffer full (ENOBUFS) — gs_usb's kernel-side TX queue + # is small. python-can chains the OSError via `raise ... from`, + # so the original errno is on __cause__. + for attempt in range(4): + try: + self._bus.send(msg) + return + except can.CanOperationError as e: + cause = e.__cause__ or e + if getattr(cause, "errno", None) == errno.ENOBUFS and attempt < 3: + time.sleep(0.001 * (attempt + 1)) + else: + raise + + def _rx_loop(self) -> None: + assert self._bus is not None + while not self._rx_stop.is_set(): + msg = self._bus.recv(timeout=0.05) + if msg is None: + continue + motor = self._by_recv.get(int(msg.arbitration_id)) + if motor is None: + continue + state = parse_state_frame(motor.motor_type, bytes(msg.data)) + if state is None: + continue + with self._state_lock: + self._states[motor.effective_recv_id] = state + + +__all__ = [ + "CTRL_MODE_MIT", + "KD_MAX", + "KD_MIN", + "KP_MAX", + "KP_MIN", + "DamiaoMotor", + "MotorState", + "MotorType", + "OpenArmBus", + "float_to_uint", + "pack_mit_frame", + "pack_write_param_frame", + "parse_state_frame", + "uint_to_float", +] diff --git a/dimos/hardware/manipulators/openarm/test_driver.py b/dimos/hardware/manipulators/openarm/test_driver.py new file mode 100644 index 0000000000..c65a972bd6 --- /dev/null +++ b/dimos/hardware/manipulators/openarm/test_driver.py @@ -0,0 +1,270 @@ +# 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. + +"""Unit tests for the Damiao MIT-mode driver — no hardware required. + +Uses ``can.Bus(interface="virtual")`` for loopback. +""" + +from __future__ import annotations + +import struct +import time + +import pytest + +can = pytest.importorskip("can") + +from dimos.hardware.manipulators.openarm.driver import ( + CTRL_MODE_MIT, + KD_MAX, + KP_MAX, + DamiaoMotor, + MotorType, + OpenArmBus, + float_to_uint, + pack_mit_frame, + pack_write_param_frame, + parse_state_frame, + uint_to_float, +) + + +def test_float_to_uint_endpoints_and_roundtrip() -> None: + # Endpoints + assert float_to_uint(-12.5, -12.5, 12.5, 16) == 0 + assert float_to_uint(12.5, -12.5, 12.5, 16) == (1 << 16) - 1 + # Midpoint is half the full range (rounded down) + mid = float_to_uint(0.0, -12.5, 12.5, 16) + assert mid in ((1 << 16) // 2 - 1, (1 << 16) // 2) + # Out-of-range clamps + assert float_to_uint(-100.0, -12.5, 12.5, 16) == 0 + assert float_to_uint(100.0, -12.5, 12.5, 16) == (1 << 16) - 1 + + +def test_roundtrip_all_gain_ranges() -> None: + # Quantization error should be tiny + for bits, lo, hi in [(16, -12.5, 12.5), (12, 0.0, KP_MAX), (12, 0.0, KD_MAX)]: + step = (hi - lo) / ((1 << bits) - 1) + for k in range(0, 1 << bits, max(1, (1 << bits) // 50)): + x = lo + k * step + u = float_to_uint(x, lo, hi, bits) + x2 = uint_to_float(u, lo, hi, bits) + assert abs(x - x2) <= step + + +def test_mit_frame_kp_kd_zero_and_pos_zero() -> None: + # q=dq=kp=kd=tau=0 → q_u = 32767 (16-bit midpoint), dq_u = 2047 (12-bit), + # tau_u = 2047. kp_u = kd_u = 0 (min of their 0-positive range). + data = pack_mit_frame(MotorType.DM4310, 0.0, 0.0, 0.0, 0.0, 0.0) + assert len(data) == 8 + # Reconstruct fields from bytes + q_u = (data[0] << 8) | data[1] + dq_u = (data[2] << 4) | (data[3] >> 4) + kp_u = ((data[3] & 0xF) << 8) | data[4] + kd_u = (data[5] << 4) | (data[6] >> 4) + tau_u = ((data[6] & 0xF) << 8) | data[7] + assert kp_u == 0 + assert kd_u == 0 + # 16-bit midpoint of symmetric range + assert q_u in (32767, 32768) + assert dq_u in (2047, 2048) + assert tau_u in (2047, 2048) + + +def test_mit_frame_full_positive() -> None: + # Command at every max → every _u field saturates. + data = pack_mit_frame(MotorType.DM4310, 12.5, 30.0, 500.0, 5.0, 10.0) + q_u = (data[0] << 8) | data[1] + dq_u = (data[2] << 4) | (data[3] >> 4) + kp_u = ((data[3] & 0xF) << 8) | data[4] + kd_u = (data[5] << 4) | (data[6] >> 4) + tau_u = ((data[6] & 0xF) << 8) | data[7] + assert q_u == 0xFFFF + assert dq_u == 0xFFF + assert kp_u == 0xFFF + assert kd_u == 0xFFF + assert tau_u == 0xFFF + + +def test_parse_state_roundtrip() -> None: + # Build a synthetic reply frame with known values and verify decode. + # Byte layout for state: [echo, q_hi, q_lo, dq_hi, dq_lo|tau_hi, tau_lo, t_mos, t_rotor] + motor = MotorType.DM4340 + p_max, v_max, t_max = 12.5, 8.0, 28.0 + q_u = float_to_uint(0.3, -p_max, p_max, 16) + dq_u = float_to_uint(-1.0, -v_max, v_max, 12) + tau_u = float_to_uint(2.0, -t_max, t_max, 12) + data = bytes( + [ + 0x03, + (q_u >> 8) & 0xFF, + q_u & 0xFF, + (dq_u >> 4) & 0xFF, + ((dq_u & 0xF) << 4) | ((tau_u >> 8) & 0xF), + tau_u & 0xFF, + 33, + 28, + ] + ) + state = parse_state_frame(motor, data) + assert state is not None + assert abs(state.q - 0.3) < 0.001 + assert abs(state.dq - (-1.0)) < 0.01 + assert abs(state.tau - 2.0) < 0.02 + assert state.t_mos == 33 + assert state.t_rotor == 28 + + +def test_parse_state_rejects_short_frames() -> None: + assert parse_state_frame(MotorType.DM4310, b"\x00" * 4) is None + + +def test_pack_write_param_ctrl_mode_mit() -> None: + data = pack_write_param_frame(0x05, 10, CTRL_MODE_MIT) + assert data[0] == 0x05 + assert data[1] == 0x00 + assert data[2] == 0x55 + assert data[3] == 10 + assert struct.unpack(" OpenArmBus: + return OpenArmBus(channel=channel, motors=motors, fd=False, interface="virtual") + + +def test_bus_validates_unique_ids() -> None: + with pytest.raises(ValueError, match="duplicate send_id"): + OpenArmBus( + channel="v0", + motors=[ + DamiaoMotor(0x01, MotorType.DM4310), + DamiaoMotor(0x01, MotorType.DM4310), + ], + fd=False, + interface="virtual", + ) + + +def test_bus_empty_motor_list_rejected() -> None: + with pytest.raises(ValueError): + OpenArmBus(channel="v0", motors=[], fd=False, interface="virtual") + + +def test_rx_thread_populates_state_cache() -> None: + # Two peers on the same virtual channel loop back to each other. + motors = [ + DamiaoMotor(0x01, MotorType.DM8006), + DamiaoMotor(0x05, MotorType.DM4310), + ] + bus = _make_bus("openarm-test-rx", motors) + # A raw sender on the same virtual channel injects state replies. + sender = can.Bus(interface="virtual", channel="openarm-test-rx") + try: + bus.open() + # Forge a reply for motor 0x01 (recv 0x11) at q = 0.25 rad + q_u = float_to_uint(0.25, -12.5, 12.5, 16) + dq_u = float_to_uint(0.0, -45.0, 45.0, 12) + tau_u = float_to_uint(0.0, -40.0, 40.0, 12) + payload = bytes( + [ + 0x01, + (q_u >> 8) & 0xFF, + q_u & 0xFF, + (dq_u >> 4) & 0xFF, + ((dq_u & 0xF) << 4) | ((tau_u >> 8) & 0xF), + tau_u & 0xFF, + 30, + 28, + ] + ) + sender.send(can.Message(arbitration_id=0x11, data=payload, is_extended_id=False)) + # Poll briefly for the RX thread to consume it + deadline = time.monotonic() + 0.5 + s = None + while s is None and time.monotonic() < deadline: + s = bus.get_state(0x01) + time.sleep(0.01) + assert s is not None, "RX thread did not pick up synthetic state reply" + assert abs(s.q - 0.25) < 0.001 + # Motor 0x05 never got a reply → state should still be None + assert bus.get_state(0x05) is None + finally: + bus.close() + sender.shutdown() + + +def test_send_mit_many_fans_out_one_per_motor() -> None: + motors = [ + DamiaoMotor(0x01, MotorType.DM8006), + DamiaoMotor(0x02, MotorType.DM8006), + DamiaoMotor(0x05, MotorType.DM4310), + ] + bus = _make_bus("openarm-test-send", motors) + listener = can.Bus(interface="virtual", channel="openarm-test-send") + try: + bus.open() + bus.send_mit_many( + [ + (0.1, 0.0, 10.0, 0.5, 0.0), + (0.2, 0.0, 10.0, 0.5, 0.0), + (0.3, 0.0, 10.0, 0.5, 0.0), + ] + ) + seen_ids: set[int] = set() + deadline = time.monotonic() + 0.5 + while len(seen_ids) < 3 and time.monotonic() < deadline: + msg = listener.recv(timeout=0.1) + if msg is not None: + seen_ids.add(int(msg.arbitration_id)) + assert seen_ids == {0x01, 0x02, 0x05} + finally: + bus.close() + listener.shutdown() + + +def test_send_mit_many_size_mismatch() -> None: + bus = _make_bus( + "openarm-test-mismatch", + [DamiaoMotor(0x01, MotorType.DM4310), DamiaoMotor(0x02, MotorType.DM4310)], + ) + try: + bus.open() + with pytest.raises(ValueError): + bus.send_mit_many([(0.0, 0.0, 0.0, 0.0, 0.0)]) + finally: + bus.close() + + +def test_enable_disable_frames_sent() -> None: + bus = _make_bus( + "openarm-test-enable", + [DamiaoMotor(0x01, MotorType.DM4310), DamiaoMotor(0x05, MotorType.DM4310)], + ) + listener = can.Bus(interface="virtual", channel="openarm-test-enable") + try: + bus.open() + bus.enable_all() + seen = {} + deadline = time.monotonic() + 0.3 + while len(seen) < 2 and time.monotonic() < deadline: + msg = listener.recv(timeout=0.1) + if msg is not None: + seen[int(msg.arbitration_id)] = bytes(msg.data) + assert set(seen) == {0x01, 0x05} + for data in seen.values(): + assert data == bytes([0xFF] * 7 + [0xFC]) + finally: + bus.close() + listener.shutdown() diff --git a/dimos/robot/catalog/openarm.py b/dimos/robot/catalog/openarm.py new file mode 100644 index 0000000000..b6e1238cf2 --- /dev/null +++ b/dimos/robot/catalog/openarm.py @@ -0,0 +1,120 @@ +# 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. + +"""OpenArm v10 robot configurations.""" + +from __future__ import annotations + +from typing import Any + +from dimos.robot.config import RobotConfig +from dimos.utils.data import LfsPath + +# Collision exclusion pairs — structural mesh overlaps in the OpenArm URDF. +# link5 and link7 collision meshes overlap by ~3mm at zero pose (and every +# other pose) — same pattern as R1 Pro's non-adjacent link overlap. +OPENARM_COLLISION_EXCLUSIONS: list[tuple[str, str]] = [ + ("openarm_left_link5", "openarm_left_link7"), + ("openarm_right_link5", "openarm_right_link7"), +] + +# LFS-backed: data/.lfs/openarm_description.tar.gz extracts to data/openarm_description/ +_OPENARM_PKG = LfsPath("openarm_description") +_OPENARM_MODEL_PATH = _OPENARM_PKG / "urdf/robot/openarm_v10_bimanual.urdf" +# Per-side URDFs: extracted from bimanual expansion, only one arm + torso each. +# Avoids phantom-arm collisions when Drake loads both sides into one world. +_OPENARM_LEFT_MODEL = _OPENARM_PKG / "urdf/robot/openarm_v10_left.urdf" +_OPENARM_RIGHT_MODEL = _OPENARM_PKG / "urdf/robot/openarm_v10_right.urdf" + +# Pre-expanded single-arm URDF for Pinocchio FK (keyboard teleop, IK, etc.) +OPENARM_V10_FK_MODEL = _OPENARM_PKG / "urdf/robot/openarm_v10_single.urdf" + + +def openarm_arm( + side: str = "left", + name: str | None = None, + *, + adapter_type: str = "mock", + address: str | None = None, + **overrides: Any, +) -> RobotConfig: + """OpenArm v10 config for one side. Uses per-side URDF (arm + torso only).""" + if side not in ("left", "right"): + raise ValueError(f"side must be 'left' or 'right', got {side!r}") + + resolved_name = name or f"{side}_arm" + # Pre-expanded bimanual URDF uses openarm_{side}_* naming. + joint_names = [f"openarm_{side}_joint{i}" for i in range(1, 8)] + ee_link = f"openarm_{side}_link7" + + defaults: dict[str, Any] = { + "name": resolved_name, + "model_path": _OPENARM_LEFT_MODEL if side == "left" else _OPENARM_RIGHT_MODEL, + "end_effector_link": ee_link, + "adapter_type": adapter_type, + "address": address, + "joint_names": joint_names, + # URDF already prefixes joints with "left_"/"right_" in bimanual mode, + # so suppress RobotConfig's automatic "{name}_" prefix. + "joint_prefix": "", + "base_link": "openarm_body_link0", + "home_joints": [0.0] * 7, + "base_pose": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0], + "package_paths": {"openarm_description": _OPENARM_PKG}, + "collision_exclusion_pairs": OPENARM_COLLISION_EXCLUSIONS, + "auto_convert_meshes": True, + "max_velocity": 0.5, + "max_acceleration": 1.0, + "adapter_kwargs": {"side": side}, + } + # Merge adapter_kwargs rather than replace, so callers can add keys + # (e.g. auto_set_mit_mode) without clobbering the catalog's "side". + if "adapter_kwargs" in overrides: + defaults["adapter_kwargs"] = { + **defaults["adapter_kwargs"], + **overrides.pop("adapter_kwargs"), + } + defaults.update(overrides) + return RobotConfig(**defaults) + + +def openarm_single( + name: str = "arm", + *, + adapter_type: str = "mock", + address: str | None = None, + **overrides: Any, +) -> RobotConfig: + """Single-arm config (keyboard teleop, cartesian IK). Use openarm_arm() for bimanual.""" + defaults: dict[str, Any] = { + "name": name, + "model_path": OPENARM_V10_FK_MODEL, + "end_effector_link": "openarm_left_link7", + "adapter_type": adapter_type, + "address": address, + "joint_names": [f"openarm_left_joint{i}" for i in range(1, 8)], + "joint_prefix": "", + "base_link": "openarm_body_link0", + "home_joints": [0.0] * 7, + "package_paths": {"openarm_description": _OPENARM_PKG}, + "auto_convert_meshes": True, + "max_velocity": 0.5, + "max_acceleration": 1.0, + "adapter_kwargs": {"side": "left"}, + } + defaults.update(overrides) + return RobotConfig(**defaults) + + +__all__ = ["OPENARM_V10_FK_MODEL", "openarm_arm", "openarm_single"] diff --git a/dimos/robot/manipulators/openarm/blueprints.py b/dimos/robot/manipulators/openarm/blueprints.py new file mode 100644 index 0000000000..5b3094c0cc --- /dev/null +++ b/dimos/robot/manipulators/openarm/blueprints.py @@ -0,0 +1,220 @@ +# 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. + +"""OpenArm blueprints. Flip LEFT_CAN / RIGHT_CAN below if arms come up swapped.""" + +from __future__ import annotations + +from dimos.control.coordinator import ControlCoordinator +from dimos.core.coordination.blueprints import autoconnect +from dimos.core.transport import LCMTransport +from dimos.manipulation.manipulation_module import ManipulationModule +from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped +from dimos.msgs.sensor_msgs.JointState import JointState +from dimos.robot.catalog.openarm import ( + OPENARM_V10_FK_MODEL, + openarm_arm as _openarm, + openarm_single as _openarm_single, +) +from dimos.teleop.keyboard.keyboard_teleop_module import KeyboardTeleopModule + +# ── Mock bimanual: no hardware, great for verifying wiring ───────────── +_mock_left = _openarm(side="left") +_mock_right = _openarm(side="right") + +coordinator_openarm_mock = ControlCoordinator.blueprint( + hardware=[_mock_left.to_hardware_component(), _mock_right.to_hardware_component()], + tasks=[ + _mock_left.to_task_config(), + _mock_right.to_task_config(), + ], +).transports( + { + ("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState), + } +) + +# ── Single-arm hardware blueprints (first real bring-up targets) ─────── +# CAN interface each physical arm is on. Linux assigns can0/can1 in USB +# enumeration order which isn't guaranteed stable — if the arms come up +# swapped, flip these two values. +LEFT_CAN = "can1" +RIGHT_CAN = "can0" + +# Flip to False to skip the CTRL_MODE=MIT write at connect-time — useful for +# verifying the setting persists across power cycles. Leave True for normal +# operation (idempotent; ensures motors work even if they were reflashed / +# replaced / factory-reset). +AUTO_SET_MIT_MODE = True + +_ADAPTER_KWARGS = {"auto_set_mit_mode": AUTO_SET_MIT_MODE} +_left_hw = _openarm( + side="left", + address=LEFT_CAN, + adapter_type="openarm", + adapter_kwargs=_ADAPTER_KWARGS, +) +_right_hw = _openarm( + side="right", + address=RIGHT_CAN, + adapter_type="openarm", + adapter_kwargs=_ADAPTER_KWARGS, +) + +coordinator_openarm_left = ControlCoordinator.blueprint( + hardware=[_left_hw.to_hardware_component()], + tasks=[_left_hw.to_task_config()], +).transports( + { + ("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState), + } +) + +coordinator_openarm_right = ControlCoordinator.blueprint( + hardware=[_right_hw.to_hardware_component()], + tasks=[_right_hw.to_task_config()], +).transports( + { + ("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState), + } +) + +# ── Bimanual hardware blueprint ──────────────────────────────────────── +coordinator_openarm_bimanual = ControlCoordinator.blueprint( + hardware=[_left_hw.to_hardware_component(), _right_hw.to_hardware_component()], + tasks=[ + _left_hw.to_task_config(), + _right_hw.to_task_config(), + ], +).transports( + { + ("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState), + } +) + + +# ── Planner + coordinator (mock): Drake plans, mock adapters execute ──── +# Great for visualizing motions in Meshcat with no hardware. +openarm_mock_planner_coordinator = autoconnect( + ManipulationModule.blueprint( + robots=[_mock_left.to_robot_model_config(), _mock_right.to_robot_model_config()], + planning_timeout=10.0, + enable_viz=True, + ), + ControlCoordinator.blueprint( + hardware=[_mock_left.to_hardware_component(), _mock_right.to_hardware_component()], + tasks=[ + _mock_left.to_task_config(), + _mock_right.to_task_config(), + ], + ), +).transports( + { + ("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState), + } +) + +# ── Planner + coordinator (real hw): plan & execute on both arms ──────── +openarm_planner_coordinator = autoconnect( + ManipulationModule.blueprint( + robots=[_left_hw.to_robot_model_config(), _right_hw.to_robot_model_config()], + planning_timeout=10.0, + enable_viz=True, + ), + ControlCoordinator.blueprint( + hardware=[_left_hw.to_hardware_component(), _right_hw.to_hardware_component()], + tasks=[ + _left_hw.to_task_config(), + _right_hw.to_task_config(), + ], + ), +).transports( + { + ("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState), + } +) + + +# ── Keyboard teleop (single arm, mock) ────────────────────────────────── +# pygame keyboard UI → Cartesian IK (Drake) → mock coordinator execution, +# with Drake/Meshcat visualization. Good for testing the single-arm URDF +# and IK without touching hardware. +_teleop_cfg = _openarm_single(name="arm") + +keyboard_teleop_openarm_mock = autoconnect( + KeyboardTeleopModule.blueprint(model_path=OPENARM_V10_FK_MODEL, ee_joint_id=_teleop_cfg.dof), + ControlCoordinator.blueprint( + hardware=[_teleop_cfg.to_hardware_component()], + tasks=[ + _teleop_cfg.to_task_config( + task_type="cartesian_ik", + task_name="cartesian_ik_arm", + model_path=OPENARM_V10_FK_MODEL, + ee_joint_id=_teleop_cfg.dof, + ), + ], + ), + ManipulationModule.blueprint( + robots=[_teleop_cfg.to_robot_model_config()], + enable_viz=True, + ), +).transports( + { + ("cartesian_command", PoseStamped): LCMTransport( + "/coordinator/cartesian_command", PoseStamped + ), + ("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState), + } +) + +# ── Keyboard teleop (single arm, real hw on can0) ─────────────────────── +_teleop_hw_cfg = _openarm_single(name="arm", adapter_type="openarm", address=LEFT_CAN) + +keyboard_teleop_openarm = autoconnect( + KeyboardTeleopModule.blueprint(model_path=OPENARM_V10_FK_MODEL, ee_joint_id=_teleop_hw_cfg.dof), + ControlCoordinator.blueprint( + hardware=[_teleop_hw_cfg.to_hardware_component()], + tasks=[ + _teleop_hw_cfg.to_task_config( + task_type="cartesian_ik", + task_name="cartesian_ik_arm", + model_path=OPENARM_V10_FK_MODEL, + ee_joint_id=_teleop_hw_cfg.dof, + ), + ], + ), + ManipulationModule.blueprint( + robots=[_teleop_hw_cfg.to_robot_model_config()], + enable_viz=True, + ), +).transports( + { + ("cartesian_command", PoseStamped): LCMTransport( + "/coordinator/cartesian_command", PoseStamped + ), + ("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState), + } +) + + +__all__ = [ + "coordinator_openarm_bimanual", + "coordinator_openarm_left", + "coordinator_openarm_mock", + "coordinator_openarm_right", + "keyboard_teleop_openarm", + "keyboard_teleop_openarm_mock", + "openarm_mock_planner_coordinator", + "openarm_planner_coordinator", +] diff --git a/dimos/robot/manipulators/openarm/scripts/openarm_can_probe.py b/dimos/robot/manipulators/openarm/scripts/openarm_can_probe.py new file mode 100755 index 0000000000..9c740ef485 --- /dev/null +++ b/dimos/robot/manipulators/openarm/scripts/openarm_can_probe.py @@ -0,0 +1,206 @@ +#!/usr/bin/env python3 +# Copyright 2025-2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Probe an OpenArm on a SocketCAN interface. + +Enumerates all 8 expected Damiao motors (7 arm joints + gripper) on one CAN bus +(classical by default, use --fd for CAN-FD), enables each, reads back one state +frame, then disables. Phase-0 hardware-verification script. + +Run AFTER bringing the bus up with dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh. + +Usage: + python dimos/robot/manipulators/openarm/scripts/openarm_can_probe.py --channel can0 + python dimos/robot/manipulators/openarm/scripts/openarm_can_probe.py --channel can1 --ids 1,2,3,4,5,6,7 +""" + +from __future__ import annotations + +import argparse +import sys +import time + +try: + import can +except ImportError: + sys.exit("python-can not installed. Run: pip install 'python-can>=4.3'") + +# ---- Damiao motor limit tables (from enactic/openarm_can dm_motor_constants.hpp) +# [p_max rad, v_max rad/s, t_max Nm] +LIMITS: dict[str, tuple[float, float, float]] = { + "DM4310": (12.5, 30.0, 10.0), + "DM4340": (12.5, 8.0, 28.0), + "DM8006": (12.5, 45.0, 40.0), +} + +# OpenArm v10 per-joint motor assignment (derived from joint_limits.yaml effort column) +DEFAULT_MOTORS: list[tuple[int, str]] = [ + (0x01, "DM8006"), # joint1 + (0x02, "DM8006"), # joint2 + (0x03, "DM4340"), # joint3 + (0x04, "DM4340"), # joint4 + (0x05, "DM4310"), # joint5 + (0x06, "DM4310"), # joint6 + (0x07, "DM4310"), # joint7 + (0x08, "DM4310"), # gripper +] + +ENABLE = bytes([0xFF] * 7 + [0xFC]) +DISABLE = bytes([0xFF] * 7 + [0xFD]) + +FD = False # set by --fd at runtime; defaults to classical CAN @ 1 Mbit + + +def uint_to_float(x: int, lo: float, hi: float, bits: int) -> float: + return x / ((1 << bits) - 1) * (hi - lo) + lo + + +def parse_state(motor_type: str, data: bytes) -> tuple[float, float, float, int, int] | None: + """Decode an 8-byte DM motor state reply. Returns (q, dq, tau, t_mos, t_rotor).""" + if len(data) < 8: + return None + p_max, v_max, t_max = LIMITS[motor_type] + q_u = (data[1] << 8) | data[2] + dq_u = (data[3] << 4) | (data[4] >> 4) + tau_u = ((data[4] & 0x0F) << 8) | data[5] + q = uint_to_float(q_u, -p_max, p_max, 16) + dq = uint_to_float(dq_u, -v_max, v_max, 12) + tau = uint_to_float(tau_u, -t_max, t_max, 12) + return q, dq, tau, data[6], data[7] + + +def probe_motor( + bus: can.BusABC, send_id: int, recv_id: int, motor_type: str, timeout: float = 0.2 +) -> bool: + """Enable motor, wait for state reply on recv_id, print result, disable.""" + # Flush any stale frames + while bus.recv(0.0) is not None: + pass + + bus.send( + can.Message( + arbitration_id=send_id, data=ENABLE, is_extended_id=False, is_fd=FD, bitrate_switch=FD + ) + ) + t0 = time.monotonic() + while time.monotonic() - t0 < timeout: + msg = bus.recv(timeout - (time.monotonic() - t0)) + if msg is None: + break + if msg.arbitration_id != recv_id: + continue + parsed = parse_state(motor_type, bytes(msg.data)) + if parsed is None: + print(f" 0x{send_id:02X} ({motor_type}): short reply {list(msg.data)}") + bus.send( + can.Message( + arbitration_id=send_id, + data=DISABLE, + is_extended_id=False, + is_fd=FD, + bitrate_switch=FD, + ) + ) + return False + q, dq, tau, t_mos, t_rot = parsed + print( + f" 0x{send_id:02X} ({motor_type:>6}): " + f"q={q:+.3f} rad dq={dq:+.3f} rad/s tau={tau:+.3f} Nm " + f"T_mos={t_mos}C T_rotor={t_rot}C" + ) + bus.send( + can.Message( + arbitration_id=send_id, + data=DISABLE, + is_extended_id=False, + is_fd=FD, + bitrate_switch=FD, + ) + ) + return True + + print( + f" 0x{send_id:02X} ({motor_type:>6}): NO REPLY on 0x{recv_id:02X} within {timeout * 1e3:.0f}ms" + ) + bus.send( + can.Message( + arbitration_id=send_id, data=DISABLE, is_extended_id=False, is_fd=FD, bitrate_switch=FD + ) + ) + return False + + +def main() -> int: + ap = argparse.ArgumentParser( + description=__doc__, formatter_class=argparse.RawDescriptionHelpFormatter + ) + ap.add_argument("--channel", default="can0", help="SocketCAN interface (default: can0)") + ap.add_argument( + "--fd", + action="store_true", + help="Use CAN-FD (requires FD-capable adapter). Default is classical CAN @ 1 Mbit, which is what most gs_usb adapters support.", + ) + ap.add_argument("--ids", default=None, help="Comma-separated send IDs to probe (default: 1..8)") + ap.add_argument("--timeout", type=float, default=0.2, help="Reply timeout per motor (s)") + args = ap.parse_args() + + global FD + FD = args.fd + motors = DEFAULT_MOTORS + if args.ids: + wanted = {int(x, 0) for x in args.ids.split(",")} + motors = [m for m in DEFAULT_MOTORS if m[0] in wanted] + + # Preflight: is the interface up? + try: + flags = int(open(f"/sys/class/net/{args.channel}/flags").read().strip(), 16) + iface_up = bool(flags & 0x1) + except OSError: + print(f"ERROR: interface '{args.channel}' not found", file=sys.stderr) + return 1 + if not iface_up: + print(f"ERROR: SocketCAN interface '{args.channel}' is DOWN.", file=sys.stderr) + print( + f" Run: sudo ./dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh {args.channel}", + file=sys.stderr, + ) + return 1 + + print(f"Opening {args.channel} ({'CAN-FD' if FD else 'classical CAN'})...") + try: + bus = can.Bus(interface="socketcan", channel=args.channel, fd=FD) + except Exception as e: + print(f"ERROR opening {args.channel}: {e}", file=sys.stderr) + print( + " Did you run 'sudo ./dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh' first?", + file=sys.stderr, + ) + return 1 + + try: + print(f"Probing {len(motors)} motor(s) on {args.channel}:") + ok = 0 + for send_id, motor_type in motors: + recv_id = send_id | 0x10 + if probe_motor(bus, send_id, recv_id, motor_type, args.timeout): + ok += 1 + print(f"\n{ok}/{len(motors)} motors replied.") + return 0 if ok == len(motors) else 2 + finally: + bus.shutdown() + + +if __name__ == "__main__": + sys.exit(main()) diff --git a/dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh b/dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh new file mode 100755 index 0000000000..d25fc41e43 --- /dev/null +++ b/dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh @@ -0,0 +1,36 @@ +#!/usr/bin/env bash +# Bring up CAN interfaces for OpenArm. Default is classical CAN @ 1 Mbit, +# which is what most gs_usb (OpenMoko / Geschwister Schneider) USB-CAN +# adapters support. Use MODE=fd if you have a CAN-FD-capable adapter. +# Run with sudo or as root. +# +# Usage: +# sudo ./dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh # classical 1M, can0 and can1 +# sudo ./dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh can0 # single interface +# sudo MODE=fd ./dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh can0 # CAN-FD 1M/5M +set -euo pipefail + +BITRATE=1000000 +DBITRATE=5000000 +MODE="${MODE:-classical}" # classical | fd +IFACES_ARG="${*:-can0 can1}" +# shellcheck disable=SC2206 +IFACES=(${IFACES_ARG[@]}) + +for IF in "${IFACES[@]}"; do + if ! ip link show "$IF" >/dev/null 2>&1; then + echo "[skip] $IF not present" + continue + fi + ip link set "$IF" down || true + if [ "$MODE" = "classical" ]; then + echo "[up ] $IF ${BITRATE} (classical CAN)" + ip link set "$IF" type can bitrate "$BITRATE" + else + echo "[up ] $IF ${BITRATE}/${DBITRATE} fd on" + ip link set "$IF" type can bitrate "$BITRATE" dbitrate "$DBITRATE" fd on + fi + ip link set "$IF" up + ip link set "$IF" txqueuelen 1000 + ip -details link show "$IF" | grep -E "can |bitrate" || true +done diff --git a/dimos/robot/manipulators/openarm/scripts/openarm_set_mit_mode.py b/dimos/robot/manipulators/openarm/scripts/openarm_set_mit_mode.py new file mode 100755 index 0000000000..04bf3912a3 --- /dev/null +++ b/dimos/robot/manipulators/openarm/scripts/openarm_set_mit_mode.py @@ -0,0 +1,140 @@ +#!/usr/bin/env python3 +# Copyright 2025-2026 Dimensional Inc. +# +# Licensed under the Apache License, Version 2.0 (the "License"); +# you may not use this file except in compliance with the License. +# You may obtain a copy of the License at +# +# http://www.apache.org/licenses/LICENSE-2.0 +# +# Unless required by applicable law or agreed to in writing, software +# distributed under the License is distributed on an "AS IS" BASIS, +# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +# See the License for the specific language governing permissions and +# limitations under the License. + +"""Write CTRL_MODE = MIT (1) to one or all OpenArm motors. + +Damiao motors have a persistent CTRL_MODE register (RID=10). If a motor was +previously configured in POS_VEL (2) / VEL (3) / POS_FORCE (4) mode, it will +respond to enable/disable but IGNORE MIT control frames — exactly the +"motor doesn't move, error grows" symptom. + +This script writes CTRL_MODE=1 (MIT) via the 0x7FF broadcast-write frame +format used by enactic/openarm_can: + + ID=0x7FF data = [id_lo, id_hi, 0x55, RID=10, val[0], val[1], val[2], val[3]] + +Run once per motor after CAN bring-up. The value is persistent across power +cycles. + +Usage: + # All 8 motors on can0 (classical CAN @ 1 Mbit, default) + python dimos/robot/manipulators/openarm/scripts/openarm_set_mit_mode.py --channel can0 + + # Single motor + python dimos/robot/manipulators/openarm/scripts/openarm_set_mit_mode.py --channel can0 --id 0x05 + + # CAN-FD (only if your adapter supports it) + python dimos/robot/manipulators/openarm/scripts/openarm_set_mit_mode.py --channel can0 --fd +""" + +from __future__ import annotations + +import argparse +import struct +import sys +import time + +try: + import can +except ImportError: + sys.exit("python-can not installed") + +RID_CTRL_MODE = 10 +MIT_MODE = 1 +DEFAULT_IDS = [0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08] + + +def write_ctrl_mode(bus: can.BusABC, send_id: int, fd: bool) -> bool: + val = struct.pack("> 8) & 0xFF, 0x55, RID_CTRL_MODE, val[0], val[1], val[2], val[3]] + ) + # Flush + while bus.recv(0.0) is not None: + pass + bus.send( + can.Message( + arbitration_id=0x7FF, data=data, is_extended_id=False, is_fd=fd, bitrate_switch=fd + ) + ) + # Wait for ack on 0x7FF (per openarm_can param response) + t0 = time.monotonic() + while time.monotonic() - t0 < 0.2: + msg = bus.recv(0.2 - (time.monotonic() - t0)) + if msg is None: + break + # Reply on 0x7FF: [id_lo, id_hi, 0x33|0x55, rid, value[0..3]] + if msg.arbitration_id != 0x7FF or len(msg.data) < 8: + continue + if msg.data[2] not in (0x33, 0x55): + continue + if msg.data[0] != (send_id & 0xFF) or msg.data[1] != ((send_id >> 8) & 0xFF): + continue # ack from a different motor + rid = msg.data[3] + if rid == RID_CTRL_MODE: + echoed = int(struct.unpack(" int: + ap = argparse.ArgumentParser( + description=__doc__, formatter_class=argparse.RawDescriptionHelpFormatter + ) + ap.add_argument("--channel", default="can0") + ap.add_argument("--fd", action="store_true", help="Use CAN-FD (default: classical CAN)") + ap.add_argument( + "--id", type=lambda s: int(s, 0), default=None, help="Single send ID (default: all 8)" + ) + args = ap.parse_args() + + fd = args.fd + ids = [args.id] if args.id is not None else DEFAULT_IDS + + # Preflight: is the interface up? + try: + flags = int(open(f"/sys/class/net/{args.channel}/flags").read().strip(), 16) + except OSError: + print(f"ERROR: interface '{args.channel}' not found", file=sys.stderr) + return 1 + if not (flags & 0x1): + print(f"ERROR: SocketCAN interface '{args.channel}' is DOWN.", file=sys.stderr) + print( + f" Run: sudo ./dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh {args.channel}", + file=sys.stderr, + ) + return 1 + + print(f"Opening {args.channel} ({'CAN-FD' if fd else 'classical'})") + bus = can.Bus(interface="socketcan", channel=args.channel, fd=fd) + try: + ok = 0 + for i in ids: + if write_ctrl_mode(bus, i, fd): + ok += 1 + time.sleep(0.05) + print(f"\n{ok}/{len(ids)} motors set to MIT mode.") + return 0 if ok == len(ids) else 2 + finally: + bus.shutdown() + + +if __name__ == "__main__": + sys.exit(main()) diff --git a/dimos/stream/audio/stt/node_whisper.py b/dimos/stream/audio/stt/node_whisper.py index e162d150a1..2c6cc1b29a 100644 --- a/dimos/stream/audio/stt/node_whisper.py +++ b/dimos/stream/audio/stt/node_whisper.py @@ -16,7 +16,6 @@ from typing import Any from reactivex import Observable, create, disposable -import whisper # type: ignore[import-untyped] from dimos.stream.audio.base import ( AbstractAudioConsumer, @@ -27,10 +26,31 @@ logger = setup_logger() +try: + import whisper # type: ignore[import-untyped] + + _USE_FASTER_WHISPER = False +except ImportError: + try: + from faster_whisper import WhisperModel # type: ignore[import-untyped] + + logger.warn( + "openai-whisper not installed, falling back to faster-whisper. " + "Install openai-whisper for the full backend: pip install openai-whisper", + ) + _USE_FASTER_WHISPER = True + except ImportError: + raise ImportError( + "No whisper backend found. " + "Install faster-whisper (pip install faster-whisper) " + "or openai-whisper (pip install dimos[whisper])." + ) + class WhisperNode(AbstractAudioConsumer, AbstractTextEmitter): """ - A node that transcribes audio using OpenAI's Whisper model and emits the transcribed text. + A node that transcribes audio using OpenAI Whisper or faster-whisper and emits + the transcribed text. Prefers openai-whisper if installed, falls back to faster-whisper. """ def __init__( @@ -41,8 +61,15 @@ def __init__( if modelopts is None: modelopts = {"language": "en", "fp16": False} self.audio_observable = None - self.modelopts = modelopts - self.model = whisper.load_model(model) + + if _USE_FASTER_WHISPER: + compute_type = "float16" if modelopts.get("fp16", False) else "int8" + modelopts = {k: v for k, v in modelopts.items() if k != "fp16"} + self.modelopts = modelopts + self.model = WhisperModel(model, device="auto", compute_type=compute_type) + else: + self.modelopts = modelopts + self.model = whisper.load_model(model) def consume_audio(self, audio_observable: Observable) -> "WhisperNode": # type: ignore[type-arg] """ @@ -73,8 +100,15 @@ def on_subscribe(observer, scheduler): # Subscribe to the audio source def on_audio_event(event: AudioEvent) -> None: try: - result = self.model.transcribe(event.data.flatten(), **self.modelopts) - observer.on_next(result["text"].strip()) + if _USE_FASTER_WHISPER: + segments, _info = self.model.transcribe( + event.data.flatten(), **self.modelopts + ) + text = " ".join(seg.text.strip() for seg in segments) + else: + result = self.model.transcribe(event.data.flatten(), **self.modelopts) + text = result["text"].strip() + observer.on_next(text) except Exception as e: logger.error(f"Error processing audio event: {e}") observer.on_error(e) diff --git a/dimos/utils/workspace.py b/dimos/utils/workspace.py new file mode 100644 index 0000000000..70d21f5a7e --- /dev/null +++ b/dimos/utils/workspace.py @@ -0,0 +1,314 @@ +# 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. + +"""Reachability + Yoshikawa-manipulability workspace analysis via Pinocchio. + +Run ``python -m dimos.utils.workspace [viz|query|suggest|interactive]``. +""" + +from __future__ import annotations + +import argparse +from pathlib import Path +import sys +import time +from typing import Any + +import numpy as np + + +class WorkspaceMap: + """Sampled reachability + manipulability map. Works on any URDF Pinocchio can load.""" + + def __init__( + self, + urdf_path: str | Path, + n_samples: int = 100_000, + *, + ee_joint_id: int | None = None, + seed: int = 42, + ) -> None: + import pinocchio + + self._pin = pinocchio + self.model = pinocchio.buildModelFromUrdf(str(urdf_path)) + self.data = self.model.createData() + self.ee_id = ee_joint_id if ee_joint_id is not None else (self.model.njoints - 1) + self.q_lo = self.model.lowerPositionLimit.copy() + self.q_hi = self.model.upperPositionLimit.copy() + self._sample(n_samples, seed) + + def _sample(self, n: int, seed: int) -> None: + rng = np.random.default_rng(seed) + self.positions = np.empty((n, 3)) + self.configs = np.empty((n, self.model.nq)) + self.manipulability = np.empty(n) + + for i in range(n): + q = rng.uniform(self.q_lo, self.q_hi) + self._pin.forwardKinematics(self.model, self.data, q) + self._pin.computeJointJacobians(self.model, self.data, q) + + self.positions[i] = self.data.oMi[self.ee_id].translation + self.configs[i] = q + + J = self._pin.getJointJacobian( + self.model, + self.data, + self.ee_id, + self._pin.ReferenceFrame.LOCAL_WORLD_ALIGNED, + ) + JJt = J[:3, :] @ J[:3, :].T + self.manipulability[i] = np.sqrt(max(0.0, np.linalg.det(JJt))) + + def query( + self, + target: np.ndarray | tuple[float, float, float], + radius: float = 0.03, + ) -> dict[str, Any]: + """Check reachability at a Cartesian target (x,y,z).""" + target = np.asarray(target, dtype=np.float64) + dists = np.linalg.norm(self.positions - target, axis=1) + mask = dists < radius + if int(mask.sum()) == 0: + for r in (0.05, 0.08, 0.12): + mask = dists < r + if mask.sum() > 0: + break + n_nearby = int(mask.sum()) + if n_nearby == 0: + nearest = int(np.argmin(dists)) + return { + "reachable": False, + "n_configs": 0, + "mean_manipulability": 0.0, + "nearest_distance": float(dists[nearest]), + "nearest_position": self.positions[nearest].tolist(), + "nearest_config": self.configs[nearest].tolist(), + } + manip_nearby = self.manipulability[mask] + indices = np.where(mask)[0] + best_idx = indices[int(np.argmax(manip_nearby))] + return { + "reachable": True, + "n_configs": n_nearby, + "mean_manipulability": float(manip_nearby.mean()), + "max_manipulability": float(manip_nearby.max()), + "best_config": self.configs[best_idx].tolist(), + "best_position": self.positions[best_idx].tolist(), + "distance": float(dists[best_idx]), + } + + def stats(self) -> str: + """Human-readable workspace summary (bounds, reach, hull volume).""" + p = self.positions + lines = [ + "Workspace stats:", + f" Samples: {len(p):,}", + f" X range: [{p[:, 0].min():.3f}, {p[:, 0].max():.3f}] m", + f" Y range: [{p[:, 1].min():.3f}, {p[:, 1].max():.3f}] m", + f" Z range: [{p[:, 2].min():.3f}, {p[:, 2].max():.3f}] m", + f" Max reach from origin: {np.linalg.norm(p, axis=1).max():.3f} m", + f" Manipulability: [{self.manipulability.min():.4f}, {self.manipulability.max():.4f}]", + ] + try: + from scipy.spatial import ConvexHull + + hull = ConvexHull(p) + lines.append(f" Convex hull volume: {hull.volume:.4f} m³") + except Exception: + pass + return "\n".join(lines) + + +# ── Meshcat visualization helpers ────────────────────────────────────────── + + +def _colormap(values: np.ndarray) -> np.ndarray: + """Red→green colormap, clipped at 2nd/98th percentile for contrast.""" + v = values.copy() + lo, hi = np.percentile(v, 2), np.percentile(v, 98) + v = np.clip((v - lo) / (hi - lo + 1e-12), 0.0, 1.0) + colors = np.zeros((len(v), 3), dtype=np.uint8) + colors[:, 0] = ((1.0 - v) * 255).astype(np.uint8) + colors[:, 1] = (v * 255).astype(np.uint8) + colors[:, 2] = 25 + return colors + + +def render_cloud(meshcat: Any, ws: WorkspaceMap, path: str = "/workspace") -> None: + """Render a WorkspaceMap's EE positions to Drake's Meshcat, colored by manipulability.""" + from pydrake.perception import BaseField, Fields, PointCloud + + cloud = PointCloud(len(ws.positions), Fields(int(BaseField.kXYZs) | int(BaseField.kRGBs))) + cloud.mutable_xyzs()[:] = ws.positions.T.astype(np.float32) + cloud.mutable_rgbs()[:] = _colormap(ws.manipulability).T + meshcat.SetObject(path, cloud, point_size=0.004) + + +def render_target( + meshcat: Any, + pos: list[float] | tuple[float, float, float], + name: str = "target", + color: tuple[float, float, float] = (1.0, 0.0, 0.0), +) -> None: + from pydrake.geometry import Rgba, Sphere + from pydrake.math import RigidTransform + + meshcat.SetObject(f"/{name}", Sphere(0.015), Rgba(*color, 0.8)) + meshcat.SetTransform(f"/{name}", RigidTransform(list(pos))) + + +# ── CLI ──────────────────────────────────────────────────────────────────── + + +def _cmd_viz(args: argparse.Namespace) -> int: + from pydrake.geometry import Meshcat + + ws = WorkspaceMap(args.urdf, args.samples, ee_joint_id=args.ee_joint_id) + print(ws.stats()) + meshcat = Meshcat() + print(f"\nMeshcat: {meshcat.web_url()}") + print("Green = dexterous, Red = near singularity\n") + render_cloud(meshcat, ws) + print("Press Ctrl-C to exit.") + try: + while True: + time.sleep(1.0) + except KeyboardInterrupt: + pass + return 0 + + +def _cmd_query(args: argparse.Namespace) -> int: + ws = WorkspaceMap(args.urdf, args.samples, ee_joint_id=args.ee_joint_id) + result = ws.query((args.x, args.y, args.z)) + print(f"\nTarget: ({args.x:.3f}, {args.y:.3f}, {args.z:.3f})") + if result["reachable"]: + print(f" REACHABLE — {result['n_configs']} configs within 3cm") + print(f" Mean manipulability: {result['mean_manipulability']:.4f}") + print(f" Best config: {[f'{q:.3f}' for q in result['best_config']]}") + p = result["best_position"] + print(f" Best EE position: ({p[0]:.3f}, {p[1]:.3f}, {p[2]:.3f})") + else: + print(" NOT REACHABLE") + p = result["nearest_position"] + print(f" Nearest reachable point: ({p[0]:.3f}, {p[1]:.3f}, {p[2]:.3f})") + print(f" Distance to nearest: {result['nearest_distance']:.3f} m") + print(f" Nearest config: {[f'{q:.3f}' for q in result['nearest_config']]}") + return 0 + + +def _cmd_suggest(args: argparse.Namespace) -> int: + ws = WorkspaceMap(args.urdf, args.samples, ee_joint_id=args.ee_joint_id) + target = np.array([args.x, args.y, args.z]) + dists = np.linalg.norm(ws.positions - target, axis=1) + closest = np.argsort(dists)[:20] + sorted_by_manip = sorted(closest, key=lambda i: -ws.manipulability[i]) + + print(f"\nSuggested poses near ({args.x:.3f}, {args.y:.3f}, {args.z:.3f}):") + print(f"{'#':>3} {'dist':>6} {'manip':>7} {'position':>30} joint config") + print("-" * 100) + for rank, idx in enumerate(sorted_by_manip[:10], 1): + p, q = ws.positions[idx], ws.configs[idx] + pos_str = f"({p[0]:+.3f}, {p[1]:+.3f}, {p[2]:+.3f})" + q_str = "[" + ", ".join(f"{v:.2f}" for v in q) + "]" + print( + f"{rank:>3} {dists[idx]:>6.3f} {ws.manipulability[idx]:>7.4f} {pos_str:>30} {q_str}" + ) + return 0 + + +def _cmd_interactive(args: argparse.Namespace) -> int: + from pydrake.geometry import Meshcat + + ws = WorkspaceMap(args.urdf, args.samples, ee_joint_id=args.ee_joint_id) + print(ws.stats()) + meshcat = Meshcat() + print(f"\nMeshcat: {meshcat.web_url()}") + render_cloud(meshcat, ws) + print("\nType target as 'x y z' (meters), or 'q' to quit.\n") + + while True: + try: + line = input("target> ").strip() + except (EOFError, KeyboardInterrupt): + break + if line.lower() in ("q", "quit", "exit"): + break + parts = line.split() + if len(parts) != 3: + print(" Enter three floats: x y z") + continue + try: + x, y, z = (float(p) for p in parts) + except ValueError: + print(" Invalid input") + continue + + result = ws.query((x, y, z)) + if result["reachable"]: + render_target(meshcat, (x, y, z), "target", (0.0, 1.0, 0.0)) + render_target(meshcat, result["best_position"], "best_ee", (0.0, 0.5, 1.0)) + print( + f" REACHABLE — {result['n_configs']} configs, " + f"manip={result['mean_manipulability']:.4f}" + ) + print(f" Joint config: {[round(q, 3) for q in result['best_config']]}") + else: + render_target(meshcat, (x, y, z), "target", (1.0, 0.0, 0.0)) + render_target(meshcat, result["nearest_position"], "nearest", (1.0, 0.5, 0.0)) + print(f" NOT REACHABLE — nearest is {result['nearest_distance']:.3f}m away") + print(f" Nearest config: {[round(q, 3) for q in result['nearest_config']]}") + return 0 + + +def main() -> int: + ap = argparse.ArgumentParser( + description=__doc__, + formatter_class=argparse.RawDescriptionHelpFormatter, + ) + ap.add_argument("urdf", type=Path, help="Path to a URDF parseable by Pinocchio") + ap.add_argument("--samples", type=int, default=100_000) + ap.add_argument( + "--ee-joint-id", + type=int, + default=None, + help="Pinocchio joint index for the end-effector (default: last joint)", + ) + + sub = ap.add_subparsers(dest="command") + sub.add_parser("viz", help="Visualize workspace in Meshcat (default)") + sub.add_parser("interactive", help="Visualize + interactive target query") + q = sub.add_parser("query", help="Query if a target is reachable") + q.add_argument("x", type=float) + q.add_argument("y", type=float) + q.add_argument("z", type=float) + s = sub.add_parser("suggest", help="Suggest reachable poses near a target") + s.add_argument("x", type=float) + s.add_argument("y", type=float) + s.add_argument("z", type=float) + + args = ap.parse_args() + cmd = args.command or "viz" + return { + "viz": _cmd_viz, + "query": _cmd_query, + "suggest": _cmd_suggest, + "interactive": _cmd_interactive, + }[cmd](args) + + +if __name__ == "__main__": + sys.exit(main()) diff --git a/dimos/web/command-center-extension/package-lock.json b/dimos/web/command-center-extension/package-lock.json index 09f9be88b4..af52732586 100644 --- a/dimos/web/command-center-extension/package-lock.json +++ b/dimos/web/command-center-extension/package-lock.json @@ -24,7 +24,7 @@ "@types/react": "18.3.24", "@types/react-dom": "18.3.7", "@vitejs/plugin-react": "^4.3.4", - "create-foxglove-extension": "1.0.6", + "create-foxglove-extension": "^1.0.6", "eslint": "9.34.0", "prettier": "3.6.2", "react": "18.3.1", @@ -61,6 +61,7 @@ "resolved": "https://registry.npmjs.org/@babel/core/-/core-7.28.5.tgz", "integrity": "sha512-e7jT4DxYvIDLk1ZHmU/m/mB19rex9sv0c2ftBtjSBv+kVM/902eh0fINUzD7UwLLNR+jU585GxUJ8/EBfAM5fw==", "dev": true, + "peer": true, "dependencies": { "@babel/code-frame": "^7.27.1", "@babel/generator": "^7.28.5", @@ -814,9 +815,9 @@ } }, "node_modules/@eslint/config-array/node_modules/brace-expansion": { - "version": "1.1.12", - "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.12.tgz", - "integrity": "sha512-9T9UjW3r0UW5c1Q7GTwllptXwhvYmEzFhzMfZ9H7FQWt+uZePjZPjBP/W1ZEyZ1twGWom5/56TF4lPcqjnDHcg==", + "version": "1.1.14", + "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.14.tgz", + "integrity": "sha512-MWPGfDxnyzKU7rNOW9SP/c50vi3xrmrua/+6hfPbCS2ABNWfx24vPidzvC7krjU/RTo235sV776ymlsMtGKj8g==", "dev": true, "license": "MIT", "dependencies": { @@ -825,9 +826,9 @@ } }, "node_modules/@eslint/config-array/node_modules/minimatch": { - "version": "3.1.2", - "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.2.tgz", - "integrity": "sha512-J7p63hRiAjw1NDEww1W7i37+ByIrOWO5XQQAzZ3VOcL0PNybwpfmV/N05zFAzwQ9USyEcX6t3UO+K5aqBQOIHw==", + "version": "3.1.5", + "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.5.tgz", + "integrity": "sha512-VgjWUsnnT6n+NUk6eZq77zeFdpW2LWDzP6zFGrCbHXiYNul5Dzqk2HHQ5uFH2DNW5Xbp8+jVzaeNt94ssEEl4w==", "dev": true, "license": "ISC", "dependencies": { @@ -885,9 +886,9 @@ } }, "node_modules/@eslint/eslintrc/node_modules/brace-expansion": { - "version": "1.1.12", - "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.12.tgz", - "integrity": "sha512-9T9UjW3r0UW5c1Q7GTwllptXwhvYmEzFhzMfZ9H7FQWt+uZePjZPjBP/W1ZEyZ1twGWom5/56TF4lPcqjnDHcg==", + "version": "1.1.14", + "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.14.tgz", + "integrity": "sha512-MWPGfDxnyzKU7rNOW9SP/c50vi3xrmrua/+6hfPbCS2ABNWfx24vPidzvC7krjU/RTo235sV776ymlsMtGKj8g==", "dev": true, "license": "MIT", "dependencies": { @@ -896,9 +897,9 @@ } }, "node_modules/@eslint/eslintrc/node_modules/minimatch": { - "version": "3.1.2", - "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.2.tgz", - "integrity": "sha512-J7p63hRiAjw1NDEww1W7i37+ByIrOWO5XQQAzZ3VOcL0PNybwpfmV/N05zFAzwQ9USyEcX6t3UO+K5aqBQOIHw==", + "version": "3.1.5", + "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.5.tgz", + "integrity": "sha512-VgjWUsnnT6n+NUk6eZq77zeFdpW2LWDzP6zFGrCbHXiYNul5Dzqk2HHQ5uFH2DNW5Xbp8+jVzaeNt94ssEEl4w==", "dev": true, "license": "ISC", "dependencies": { @@ -1043,45 +1044,14 @@ "url": "https://github.com/sponsors/nzakas" } }, - "node_modules/@isaacs/balanced-match": { - "version": "4.0.1", - "resolved": "https://registry.npmjs.org/@isaacs/balanced-match/-/balanced-match-4.0.1.tgz", - "integrity": "sha512-yzMTt9lEb8Gv7zRioUilSglI0c0smZ9k5D65677DLWLtWJaXIS3CqcGyUFByYKlnUj6TkjLVs54fBl6+TiGQDQ==", - "dev": true, - "license": "MIT", - "engines": { - "node": "20 || >=22" - } - }, - "node_modules/@isaacs/brace-expansion": { - "version": "5.0.0", - "resolved": "https://registry.npmjs.org/@isaacs/brace-expansion/-/brace-expansion-5.0.0.tgz", - "integrity": "sha512-ZT55BDLV0yv0RBm2czMiZ+SqCGO7AvmOM3G/w2xhVPH+te0aKgFjmBvGlL1dH+ql2tgGO3MVrbb3jCKyvpgnxA==", - "dev": true, - "license": "MIT", - "dependencies": { - "@isaacs/balanced-match": "^4.0.1" - }, - "engines": { - "node": "20 || >=22" - } - }, "node_modules/@isaacs/cliui": { - "version": "8.0.2", - "resolved": "https://registry.npmjs.org/@isaacs/cliui/-/cliui-8.0.2.tgz", - "integrity": "sha512-O8jcjabXaleOG9DQ0+ARXWZBTfnP4WNAqzuiJK7ll44AmxGKv/J2M4TPjxjY3znBCfvBXFzucm1twdyFybFqEA==", + "version": "9.0.0", + "resolved": "https://registry.npmjs.org/@isaacs/cliui/-/cliui-9.0.0.tgz", + "integrity": "sha512-AokJm4tuBHillT+FpMtxQ60n8ObyXBatq7jD2/JA9dxbDDokKQm8KMht5ibGzLVU9IJDIKK4TPKgMHEYMn3lMg==", "dev": true, - "license": "ISC", - "dependencies": { - "string-width": "^5.1.2", - "string-width-cjs": "npm:string-width@^4.2.0", - "strip-ansi": "^7.0.1", - "strip-ansi-cjs": "npm:strip-ansi@^6.0.1", - "wrap-ansi": "^8.1.0", - "wrap-ansi-cjs": "npm:wrap-ansi@^7.0.0" - }, + "license": "BlueOak-1.0.0", "engines": { - "node": ">=12" + "node": ">=18" } }, "node_modules/@jridgewell/gen-mapping": { @@ -1213,286 +1183,350 @@ "dev": true }, "node_modules/@rollup/rollup-android-arm-eabi": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-android-arm-eabi/-/rollup-android-arm-eabi-4.54.0.tgz", - "integrity": "sha512-OywsdRHrFvCdvsewAInDKCNyR3laPA2mc9bRYJ6LBp5IyvF3fvXbbNR0bSzHlZVFtn6E0xw2oZlyjg4rKCVcng==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-android-arm-eabi/-/rollup-android-arm-eabi-4.60.3.tgz", + "integrity": "sha512-x35CNW/ANXG3hE/EZpRU8MXX1JDN86hBb2wMGAtltkz7pc6cxgjpy1OMMfDosOQ+2hWqIkag/fGok1Yady9nGw==", "cpu": [ "arm" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "android" ] }, "node_modules/@rollup/rollup-android-arm64": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-android-arm64/-/rollup-android-arm64-4.54.0.tgz", - "integrity": "sha512-Skx39Uv+u7H224Af+bDgNinitlmHyQX1K/atIA32JP3JQw6hVODX5tkbi2zof/E69M1qH2UoN3Xdxgs90mmNYw==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-android-arm64/-/rollup-android-arm64-4.60.3.tgz", + "integrity": "sha512-xw3xtkDApIOGayehp2+Rz4zimfkaX65r4t47iy+ymQB2G4iJCBBfj0ogVg5jpvjpn8UWn/+q9tprxleYeNp3Hw==", "cpu": [ "arm64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "android" ] }, "node_modules/@rollup/rollup-darwin-arm64": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-darwin-arm64/-/rollup-darwin-arm64-4.54.0.tgz", - "integrity": "sha512-k43D4qta/+6Fq+nCDhhv9yP2HdeKeP56QrUUTW7E6PhZP1US6NDqpJj4MY0jBHlJivVJD5P8NxrjuobZBJTCRw==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-darwin-arm64/-/rollup-darwin-arm64-4.60.3.tgz", + "integrity": "sha512-vo6Y5Qfpx7/5EaamIwi0WqW2+zfiusVihKatLvtN1VFVy3D13uERk/6gZLU1UiHRL6fDXqj/ELIeVRGnvcTE1g==", "cpu": [ "arm64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "darwin" ] }, "node_modules/@rollup/rollup-darwin-x64": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-darwin-x64/-/rollup-darwin-x64-4.54.0.tgz", - "integrity": "sha512-cOo7biqwkpawslEfox5Vs8/qj83M/aZCSSNIWpVzfU2CYHa2G3P1UN5WF01RdTHSgCkri7XOlTdtk17BezlV3A==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-darwin-x64/-/rollup-darwin-x64-4.60.3.tgz", + "integrity": "sha512-D+0QGcZhBzTN82weOnsSlY7V7+RMmPuF1CkbxyMAGE8+ZHeUjyb76ZiWmBlCu//AQQONvxcqRbwZTajZKqjuOw==", "cpu": [ "x64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "darwin" ] }, "node_modules/@rollup/rollup-freebsd-arm64": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-freebsd-arm64/-/rollup-freebsd-arm64-4.54.0.tgz", - "integrity": "sha512-miSvuFkmvFbgJ1BevMa4CPCFt5MPGw094knM64W9I0giUIMMmRYcGW/JWZDriaw/k1kOBtsWh1z6nIFV1vPNtA==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-freebsd-arm64/-/rollup-freebsd-arm64-4.60.3.tgz", + "integrity": "sha512-6HnvHCT7fDyj6R0Ph7A6x8dQS/S38MClRWeDLqc0MdfWkxjiu1HSDYrdPhqSILzjTIC/pnXbbJbo+ft+gy/9hQ==", "cpu": [ "arm64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "freebsd" ] }, "node_modules/@rollup/rollup-freebsd-x64": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-freebsd-x64/-/rollup-freebsd-x64-4.54.0.tgz", - "integrity": "sha512-KGXIs55+b/ZfZsq9aR026tmr/+7tq6VG6MsnrvF4H8VhwflTIuYh+LFUlIsRdQSgrgmtM3fVATzEAj4hBQlaqQ==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-freebsd-x64/-/rollup-freebsd-x64-4.60.3.tgz", + "integrity": "sha512-KHLgC3WKlUYW3ShFKnnosZDOJ0xjg9zp7au3sIm2bs/tGBeC2ipmvRh/N7JKi0t9Ue20C0dpEshi8WUubg+cnA==", "cpu": [ "x64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "freebsd" ] }, "node_modules/@rollup/rollup-linux-arm-gnueabihf": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm-gnueabihf/-/rollup-linux-arm-gnueabihf-4.54.0.tgz", - "integrity": "sha512-EHMUcDwhtdRGlXZsGSIuXSYwD5kOT9NVnx9sqzYiwAc91wfYOE1g1djOEDseZJKKqtHAHGwnGPQu3kytmfaXLQ==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm-gnueabihf/-/rollup-linux-arm-gnueabihf-4.60.3.tgz", + "integrity": "sha512-DV6fJoxEYWJOvaZIsok7KrYl0tPvga5OZ2yvKHNNYyk/2roMLqQAbGhr78EQ5YhHpnhLKJD3S1WFusAkmUuV5g==", "cpu": [ "arm" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "linux" ] }, "node_modules/@rollup/rollup-linux-arm-musleabihf": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm-musleabihf/-/rollup-linux-arm-musleabihf-4.54.0.tgz", - "integrity": "sha512-+pBrqEjaakN2ySv5RVrj/qLytYhPKEUwk+e3SFU5jTLHIcAtqh2rLrd/OkbNuHJpsBgxsD8ccJt5ga/SeG0JmA==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm-musleabihf/-/rollup-linux-arm-musleabihf-4.60.3.tgz", + "integrity": "sha512-mQKoJAzvuOs6F+TZybQO4GOTSMUu7v0WdxEk24krQ/uUxXoPTtHjuaUuPmFhtBcM4K0ons8nrE3JyhTuCFtT/w==", "cpu": [ "arm" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "linux" ] }, "node_modules/@rollup/rollup-linux-arm64-gnu": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm64-gnu/-/rollup-linux-arm64-gnu-4.54.0.tgz", - "integrity": "sha512-NSqc7rE9wuUaRBsBp5ckQ5CVz5aIRKCwsoa6WMF7G01sX3/qHUw/z4pv+D+ahL1EIKy6Enpcnz1RY8pf7bjwng==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm64-gnu/-/rollup-linux-arm64-gnu-4.60.3.tgz", + "integrity": "sha512-Whjj2qoiJ6+OOJMGptTYazaJvjOJm+iKHpXQM1P3LzGjt7Ff++Tp7nH4N8J/BUA7R9IHfDyx4DJIflifwnbmIA==", "cpu": [ "arm64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "linux" ] }, "node_modules/@rollup/rollup-linux-arm64-musl": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm64-musl/-/rollup-linux-arm64-musl-4.54.0.tgz", - "integrity": "sha512-gr5vDbg3Bakga5kbdpqx81m2n9IX8M6gIMlQQIXiLTNeQW6CucvuInJ91EuCJ/JYvc+rcLLsDFcfAD1K7fMofg==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-arm64-musl/-/rollup-linux-arm64-musl-4.60.3.tgz", + "integrity": "sha512-4YTNHKqGng5+yiZt3mg77nmyuCfmNfX4fPmyUapBcIk+BdwSwmCWGXOUxhXbBEkFHtoN5boLj/5NON+u5QC9tg==", "cpu": [ "arm64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "linux" ] }, "node_modules/@rollup/rollup-linux-loong64-gnu": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-loong64-gnu/-/rollup-linux-loong64-gnu-4.54.0.tgz", - "integrity": "sha512-gsrtB1NA3ZYj2vq0Rzkylo9ylCtW/PhpLEivlgWe0bpgtX5+9j9EZa0wtZiCjgu6zmSeZWyI/e2YRX1URozpIw==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-loong64-gnu/-/rollup-linux-loong64-gnu-4.60.3.tgz", + "integrity": "sha512-SU3kNlhkpI4UqlUc2VXPGK9o886ZsSeGfMAX2ba2b8DKmMXq4AL7KUrkSWVbb7koVqx41Yczx6dx5PNargIrEA==", "cpu": [ "loong64" ], "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-loong64-musl": { + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-loong64-musl/-/rollup-linux-loong64-musl-4.60.3.tgz", + "integrity": "sha512-6lDLl5h4TXpB1mTf2rQWnAk/LcXrx9vBfu/DT5TIPhvMhRWaZ5MxkIc8u4lJAmBo6klTe1ywXIUHFjylW505sg==", + "cpu": [ + "loong64" + ], + "dev": true, + "license": "MIT", "optional": true, "os": [ "linux" ] }, "node_modules/@rollup/rollup-linux-ppc64-gnu": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-ppc64-gnu/-/rollup-linux-ppc64-gnu-4.54.0.tgz", - "integrity": "sha512-y3qNOfTBStmFNq+t4s7Tmc9hW2ENtPg8FeUD/VShI7rKxNW7O4fFeaYbMsd3tpFlIg1Q8IapFgy7Q9i2BqeBvA==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-ppc64-gnu/-/rollup-linux-ppc64-gnu-4.60.3.tgz", + "integrity": "sha512-BMo8bOw8evlup/8G+cj5xWtPyp93xPdyoSN16Zy90Q2QZ0ZYRhCt6ZJSwbrRzG9HApFabjwj2p25TUPDWrhzqQ==", "cpu": [ "ppc64" ], "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "linux" + ] + }, + "node_modules/@rollup/rollup-linux-ppc64-musl": { + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-ppc64-musl/-/rollup-linux-ppc64-musl-4.60.3.tgz", + "integrity": "sha512-E0L8X1dZN1/Rph+5VPF6Xj2G7JJvMACVXtamTJIDrVI44Y3K+G8gQaMEAavbqCGTa16InptiVrX6eM6pmJ+7qA==", + "cpu": [ + "ppc64" + ], + "dev": true, + "license": "MIT", "optional": true, "os": [ "linux" ] }, "node_modules/@rollup/rollup-linux-riscv64-gnu": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-riscv64-gnu/-/rollup-linux-riscv64-gnu-4.54.0.tgz", - "integrity": "sha512-89sepv7h2lIVPsFma8iwmccN7Yjjtgz0Rj/Ou6fEqg3HDhpCa+Et+YSufy27i6b0Wav69Qv4WBNl3Rs6pwhebQ==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-riscv64-gnu/-/rollup-linux-riscv64-gnu-4.60.3.tgz", + "integrity": "sha512-oZJ/WHaVfHUiRAtmTAeo3DcevNsVvH8mbvodjZy7D5QKvCefO371SiKRpxoDcCxB3PTRTLayWBkvmDQKTcX/sw==", "cpu": [ "riscv64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "linux" ] }, "node_modules/@rollup/rollup-linux-riscv64-musl": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-riscv64-musl/-/rollup-linux-riscv64-musl-4.54.0.tgz", - "integrity": "sha512-ZcU77ieh0M2Q8Ur7D5X7KvK+UxbXeDHwiOt/CPSBTI1fBmeDMivW0dPkdqkT4rOgDjrDDBUed9x4EgraIKoR2A==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-riscv64-musl/-/rollup-linux-riscv64-musl-4.60.3.tgz", + "integrity": "sha512-Dhbyh7j9FybM3YaTgaHmVALwA8AkUwTPccyCQ79TG9AJUsMQqgN1DDEZNr4+QUfwiWvLDumW5vdwzoeUF+TNxQ==", "cpu": [ "riscv64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "linux" ] }, "node_modules/@rollup/rollup-linux-s390x-gnu": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-s390x-gnu/-/rollup-linux-s390x-gnu-4.54.0.tgz", - "integrity": "sha512-2AdWy5RdDF5+4YfG/YesGDDtbyJlC9LHmL6rZw6FurBJ5n4vFGupsOBGfwMRjBYH7qRQowT8D/U4LoSvVwOhSQ==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-s390x-gnu/-/rollup-linux-s390x-gnu-4.60.3.tgz", + "integrity": "sha512-cJd1X5XhHHlltkaypz1UcWLA8AcoIi1aWhsvaWDskD1oz2eKCypnqvTQ8ykMNI0RSmm7NkTdSqSSD7zM0xa6Ig==", "cpu": [ "s390x" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "linux" ] }, "node_modules/@rollup/rollup-linux-x64-gnu": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-x64-gnu/-/rollup-linux-x64-gnu-4.54.0.tgz", - "integrity": "sha512-WGt5J8Ij/rvyqpFexxk3ffKqqbLf9AqrTBbWDk7ApGUzaIs6V+s2s84kAxklFwmMF/vBNGrVdYgbblCOFFezMQ==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-x64-gnu/-/rollup-linux-x64-gnu-4.60.3.tgz", + "integrity": "sha512-DAZDBHQfG2oQuhY7mc6I3/qB4LU2fQCjRvxbDwd/Jdvb9fypP4IJ4qmtu6lNjes6B531AI8cg1aKC2di97bUxA==", "cpu": [ "x64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "linux" ] }, "node_modules/@rollup/rollup-linux-x64-musl": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-x64-musl/-/rollup-linux-x64-musl-4.54.0.tgz", - "integrity": "sha512-JzQmb38ATzHjxlPHuTH6tE7ojnMKM2kYNzt44LO/jJi8BpceEC8QuXYA908n8r3CNuG/B3BV8VR3Hi1rYtmPiw==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-linux-x64-musl/-/rollup-linux-x64-musl-4.60.3.tgz", + "integrity": "sha512-cRxsE8c13mZOh3vP+wLDxpQBRrOHDIGOWyDL93Sy0Ga8y515fBcC2pjUfFwUe5T7tqvTvWbCpg1URM/AXdWIXA==", "cpu": [ "x64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "linux" ] }, + "node_modules/@rollup/rollup-openbsd-x64": { + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-openbsd-x64/-/rollup-openbsd-x64-4.60.3.tgz", + "integrity": "sha512-QaWcIgRxqEdQdhJqW4DJctsH6HCmo5vHxY0krHSX4jMtOqfzC+dqDGuHM87bu4H8JBeibWx7jFz+h6/4C8wA5Q==", + "cpu": [ + "x64" + ], + "dev": true, + "license": "MIT", + "optional": true, + "os": [ + "openbsd" + ] + }, "node_modules/@rollup/rollup-openharmony-arm64": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-openharmony-arm64/-/rollup-openharmony-arm64-4.54.0.tgz", - "integrity": "sha512-huT3fd0iC7jigGh7n3q/+lfPcXxBi+om/Rs3yiFxjvSxbSB6aohDFXbWvlspaqjeOh+hx7DDHS+5Es5qRkWkZg==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-openharmony-arm64/-/rollup-openharmony-arm64-4.60.3.tgz", + "integrity": "sha512-AaXwSvUi3QIPtroAUw1t5yHGIyqKEXwH54WUocFolZhpGDruJcs8c+xPNDRn4XiQsS7MEwnYsHW2l0MBLDMkWg==", "cpu": [ "arm64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "openharmony" ] }, "node_modules/@rollup/rollup-win32-arm64-msvc": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-arm64-msvc/-/rollup-win32-arm64-msvc-4.54.0.tgz", - "integrity": "sha512-c2V0W1bsKIKfbLMBu/WGBz6Yci8nJ/ZJdheE0EwB73N3MvHYKiKGs3mVilX4Gs70eGeDaMqEob25Tw2Gb9Nqyw==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-arm64-msvc/-/rollup-win32-arm64-msvc-4.60.3.tgz", + "integrity": "sha512-65LAKM/bAWDqKNEelHlcHvm2V+Vfb8C6INFxQXRHCvaVN1rJfwr4NvdP4FyzUaLqWfaCGaadf6UbTm8xJeYfEg==", "cpu": [ "arm64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "win32" ] }, "node_modules/@rollup/rollup-win32-ia32-msvc": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-ia32-msvc/-/rollup-win32-ia32-msvc-4.54.0.tgz", - "integrity": "sha512-woEHgqQqDCkAzrDhvDipnSirm5vxUXtSKDYTVpZG3nUdW/VVB5VdCYA2iReSj/u3yCZzXID4kuKG7OynPnB3WQ==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-ia32-msvc/-/rollup-win32-ia32-msvc-4.60.3.tgz", + "integrity": "sha512-EEM2gyhBF5MFnI6vMKdX1LAosE627RGBzIoGMdLloPZkXrUN0Ckqgr2Qi8+J3zip/8NVVro3/FjB+tjhZUgUHA==", "cpu": [ "ia32" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "win32" ] }, "node_modules/@rollup/rollup-win32-x64-gnu": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-x64-gnu/-/rollup-win32-x64-gnu-4.54.0.tgz", - "integrity": "sha512-dzAc53LOuFvHwbCEOS0rPbXp6SIhAf2txMP5p6mGyOXXw5mWY8NGGbPMPrs4P1WItkfApDathBj/NzMLUZ9rtQ==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-x64-gnu/-/rollup-win32-x64-gnu-4.60.3.tgz", + "integrity": "sha512-E5Eb5H/DpxaoXH++Qkv28RcUJboMopmdDUALBczvHMf7hNIxaDZqwY5lK12UK1BHacSmvupoEWGu+n993Z0y1A==", "cpu": [ "x64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "win32" ] }, "node_modules/@rollup/rollup-win32-x64-msvc": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-x64-msvc/-/rollup-win32-x64-msvc-4.54.0.tgz", - "integrity": "sha512-hYT5d3YNdSh3mbCU1gwQyPgQd3T2ne0A3KG8KSBdav5TiBg6eInVmV+TeR5uHufiIgSFg0XsOWGW5/RhNcSvPg==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/@rollup/rollup-win32-x64-msvc/-/rollup-win32-x64-msvc-4.60.3.tgz", + "integrity": "sha512-hPt/bgL5cE+Qp+/TPHBqptcAgPzgj46mPcg/16zNUmbQk0j+mOEQV/+Lqu8QRtDV3Ek95Q6FeFITpuhl6OTsAA==", "cpu": [ "x64" ], "dev": true, + "license": "MIT", "optional": true, "os": [ "win32" @@ -1842,6 +1876,7 @@ "integrity": "sha512-FXx2pKgId/WyYo2jXw63kk7/+TY7u7AziEJxJAnSFzHlqTAS3Ync6SvgYAN/k4/PQpnnVuzoMuVnByKK2qp0ag==", "dev": true, "license": "MIT", + "peer": true, "dependencies": { "@types/estree": "*", "@types/json-schema": "*" @@ -1942,6 +1977,7 @@ "integrity": "sha512-0dLEBsA1kI3OezMBF8nSsb7Nk19ZnsyE1LLhB8r27KbgU5H4pvuqZLdtE+aUkJVoXgTVuA+iLIwmZ0TuK4tx6A==", "dev": true, "license": "MIT", + "peer": true, "dependencies": { "@types/prop-types": "*", "csstype": "^3.0.2" @@ -1963,6 +1999,7 @@ "integrity": "sha512-w/EboPlBwnmOBtRbiOvzjD+wdiZdgFeo17lkltrtn7X37vagKKWJABvyfsJXTlHe6XBzugmYgd4A4nW+k8Mixw==", "dev": true, "license": "MIT", + "peer": true, "dependencies": { "@eslint-community/regexpp": "^4.10.0", "@typescript-eslint/scope-manager": "8.40.0", @@ -2003,6 +2040,7 @@ "integrity": "sha512-jCNyAuXx8dr5KJMkecGmZ8KI61KBUhkCob+SD+C+I5+Y1FWI2Y3QmY4/cxMCC5WAsZqoEtEETVhUiUMIGCf6Bw==", "dev": true, "license": "MIT", + "peer": true, "dependencies": { "@typescript-eslint/scope-manager": "8.40.0", "@typescript-eslint/types": "8.40.0", @@ -2403,6 +2441,7 @@ "integrity": "sha512-NZyJarBfL7nWwIq+FDL6Zp/yHEhePMNnnJ0y3qfieCrmNvYct8uvtiV41UvlSe6apAfk0fY1FbWx+NwfmpvtTg==", "dev": true, "license": "MIT", + "peer": true, "bin": { "acorn": "bin/acorn" }, @@ -2421,11 +2460,12 @@ } }, "node_modules/ajv": { - "version": "6.12.6", - "resolved": "https://registry.npmjs.org/ajv/-/ajv-6.12.6.tgz", - "integrity": "sha512-j3fVLgvTo527anyYyJOGTYJbG+vnnQYvE0m5mmkc1TK+nxAppkCLMIL0aZ4dblVCNoGShhm+kzE4ZUykBoMg4g==", + "version": "6.15.0", + "resolved": "https://registry.npmjs.org/ajv/-/ajv-6.15.0.tgz", + "integrity": "sha512-fgFx7Hfoq60ytK2c7DhnF8jIvzYgOMxfugjLOSMHjLIPgenqa7S7oaagATUq99mV6IYvN2tRmC0wnTYX6iPbMw==", "dev": true, "license": "MIT", + "peer": true, "dependencies": { "fast-deep-equal": "^3.1.1", "fast-json-stable-stringify": "^2.0.0", @@ -2456,9 +2496,9 @@ } }, "node_modules/ajv-formats/node_modules/ajv": { - "version": "8.17.1", - "resolved": "https://registry.npmjs.org/ajv/-/ajv-8.17.1.tgz", - "integrity": "sha512-B/gBuNg5SiMTrPkC+A2+cW0RszwxYmn6VYxB/inlBStS5nx6xHIt/ehKRhIMhqusl7a8LjQoZnjCs5vhwxOQ1g==", + "version": "8.20.0", + "resolved": "https://registry.npmjs.org/ajv/-/ajv-8.20.0.tgz", + "integrity": "sha512-Thbli+OlOj+iMPYFBVBfJ3OmCAnaSyNn4M1vz9T6Gka5Jt9ba/HIR56joy65tY6kx/FCF5VXNB819Y7/GUrBGA==", "dev": true, "license": "MIT", "dependencies": { @@ -2489,19 +2529,6 @@ "ajv": "^6.9.1" } }, - "node_modules/ansi-regex": { - "version": "6.2.0", - "resolved": "https://registry.npmjs.org/ansi-regex/-/ansi-regex-6.2.0.tgz", - "integrity": "sha512-TKY5pyBkHyADOPYlRT9Lx6F544mPl0vS5Ew7BJ45hA08Q+t3GjbueLliBWN3sMICk6+y7HdyxSzC4bWS8baBdg==", - "dev": true, - "license": "MIT", - "engines": { - "node": ">=12" - }, - "funding": { - "url": "https://github.com/chalk/ansi-regex?sponsor=1" - } - }, "node_modules/ansi-styles": { "version": "4.3.0", "resolved": "https://registry.npmjs.org/ansi-styles/-/ansi-styles-4.3.0.tgz", @@ -2742,9 +2769,9 @@ "license": "MIT" }, "node_modules/brace-expansion": { - "version": "2.0.2", - "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-2.0.2.tgz", - "integrity": "sha512-Jt0vHyM+jmUBqojB7E1NIYadt0vI0Qxjxd2TErW94wDz+E2LAm5vKMXXwg6ZZBTHPuUlDgQHKXvjGBdfcF1ZDQ==", + "version": "2.1.0", + "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-2.1.0.tgz", + "integrity": "sha512-TN1kCZAgdgweJhWWpgKYrQaMNHcDULHkWwQIspdtjV4Y5aurRdZpjAqn6yX3FPqTA9ngHCc4hJxMAMgGfve85w==", "dev": true, "license": "MIT", "dependencies": { @@ -2784,6 +2811,7 @@ } ], "license": "MIT", + "peer": true, "dependencies": { "caniuse-lite": "^1.0.30001735", "electron-to-chromium": "^1.5.204", @@ -3353,6 +3381,7 @@ "resolved": "https://registry.npmjs.org/d3-selection/-/d3-selection-3.0.0.tgz", "integrity": "sha512-fmTRWbNMmsmWq6xJV8D19U/gw/bwrHfNXxrIN+HfZgnzqTHp9jOmKMhsTUjXOJnZOdZY9Q28y4yebKzqDKlxlQ==", "license": "ISC", + "peer": true, "engines": { "node": ">=12" } @@ -3495,7 +3524,6 @@ "version": "4.4.1", "resolved": "https://registry.npmjs.org/debug/-/debug-4.4.1.tgz", "integrity": "sha512-KcKCqiftBJcZr++7ykoDIEwSa3XWowTfNPo92BYxjXiyYEVrUQh2aLyhxBCwww+heortUFxEJYcRzosstTEBYQ==", - "dev": true, "license": "MIT", "dependencies": { "ms": "^2.1.3" @@ -3622,13 +3650,6 @@ "node": ">= 0.4" } }, - "node_modules/eastasianwidth": { - "version": "0.2.0", - "resolved": "https://registry.npmjs.org/eastasianwidth/-/eastasianwidth-0.2.0.tgz", - "integrity": "sha512-I88TYZWc9XiYHRQ4/3c5rjjfgkjhLyW2luGIheGERbNQ6OY7yTybanSpDXZa8y7VUP9YmDcYa+eyq4ca7iLqWA==", - "dev": true, - "license": "MIT" - }, "node_modules/electron-to-chromium": { "version": "1.5.208", "resolved": "https://registry.npmjs.org/electron-to-chromium/-/electron-to-chromium-1.5.208.tgz", @@ -3636,13 +3657,6 @@ "dev": true, "license": "ISC" }, - "node_modules/emoji-regex": { - "version": "9.2.2", - "resolved": "https://registry.npmjs.org/emoji-regex/-/emoji-regex-9.2.2.tgz", - "integrity": "sha512-L18DaJsXSUk2+42pv8mLs5jJT2hqFkFE4j21wOmgbUqsZ2hL72NsUU785g9RXgo3s0ZNgVl42TiHp3ZtOv/Vyg==", - "dev": true, - "license": "MIT" - }, "node_modules/engine.io-client": { "version": "6.6.3", "resolved": "https://registry.npmjs.org/engine.io-client/-/engine.io-client-6.6.3.tgz", @@ -3950,6 +3964,7 @@ "integrity": "sha512-RNCHRX5EwdrESy3Jc9o8ie8Bog+PeYvvSR8sDGoZxNFTvZ4dlxUB3WzQ3bQMztFrSRODGrLLj8g6OFuGY/aiQg==", "dev": true, "license": "MIT", + "peer": true, "dependencies": { "@eslint-community/eslint-utils": "^4.2.0", "@eslint-community/regexpp": "^4.12.1", @@ -4011,6 +4026,7 @@ "integrity": "sha512-iI1f+D2ViGn+uvv5HuHVUamg8ll4tN+JRHGc6IJi4TP9Kl976C57fzPXgseXNs8v0iA8aSJpHsTWjDb9QJamGQ==", "dev": true, "license": "MIT", + "peer": true, "bin": { "eslint-config-prettier": "bin/cli.js" }, @@ -4139,9 +4155,9 @@ } }, "node_modules/eslint-plugin-import/node_modules/brace-expansion": { - "version": "1.1.12", - "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.12.tgz", - "integrity": "sha512-9T9UjW3r0UW5c1Q7GTwllptXwhvYmEzFhzMfZ9H7FQWt+uZePjZPjBP/W1ZEyZ1twGWom5/56TF4lPcqjnDHcg==", + "version": "1.1.14", + "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.14.tgz", + "integrity": "sha512-MWPGfDxnyzKU7rNOW9SP/c50vi3xrmrua/+6hfPbCS2ABNWfx24vPidzvC7krjU/RTo235sV776ymlsMtGKj8g==", "dev": true, "license": "MIT", "dependencies": { @@ -4160,9 +4176,9 @@ } }, "node_modules/eslint-plugin-import/node_modules/minimatch": { - "version": "3.1.2", - "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.2.tgz", - "integrity": "sha512-J7p63hRiAjw1NDEww1W7i37+ByIrOWO5XQQAzZ3VOcL0PNybwpfmV/N05zFAzwQ9USyEcX6t3UO+K5aqBQOIHw==", + "version": "3.1.5", + "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.5.tgz", + "integrity": "sha512-VgjWUsnnT6n+NUk6eZq77zeFdpW2LWDzP6zFGrCbHXiYNul5Dzqk2HHQ5uFH2DNW5Xbp8+jVzaeNt94ssEEl4w==", "dev": true, "license": "ISC", "dependencies": { @@ -4286,9 +4302,9 @@ } }, "node_modules/eslint-plugin-react/node_modules/brace-expansion": { - "version": "1.1.12", - "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.12.tgz", - "integrity": "sha512-9T9UjW3r0UW5c1Q7GTwllptXwhvYmEzFhzMfZ9H7FQWt+uZePjZPjBP/W1ZEyZ1twGWom5/56TF4lPcqjnDHcg==", + "version": "1.1.14", + "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.14.tgz", + "integrity": "sha512-MWPGfDxnyzKU7rNOW9SP/c50vi3xrmrua/+6hfPbCS2ABNWfx24vPidzvC7krjU/RTo235sV776ymlsMtGKj8g==", "dev": true, "license": "MIT", "dependencies": { @@ -4297,9 +4313,9 @@ } }, "node_modules/eslint-plugin-react/node_modules/minimatch": { - "version": "3.1.2", - "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.2.tgz", - "integrity": "sha512-J7p63hRiAjw1NDEww1W7i37+ByIrOWO5XQQAzZ3VOcL0PNybwpfmV/N05zFAzwQ9USyEcX6t3UO+K5aqBQOIHw==", + "version": "3.1.5", + "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.5.tgz", + "integrity": "sha512-VgjWUsnnT6n+NUk6eZq77zeFdpW2LWDzP6zFGrCbHXiYNul5Dzqk2HHQ5uFH2DNW5Xbp8+jVzaeNt94ssEEl4w==", "dev": true, "license": "ISC", "dependencies": { @@ -4394,9 +4410,9 @@ } }, "node_modules/eslint/node_modules/brace-expansion": { - "version": "1.1.12", - "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.12.tgz", - "integrity": "sha512-9T9UjW3r0UW5c1Q7GTwllptXwhvYmEzFhzMfZ9H7FQWt+uZePjZPjBP/W1ZEyZ1twGWom5/56TF4lPcqjnDHcg==", + "version": "1.1.14", + "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.14.tgz", + "integrity": "sha512-MWPGfDxnyzKU7rNOW9SP/c50vi3xrmrua/+6hfPbCS2ABNWfx24vPidzvC7krjU/RTo235sV776ymlsMtGKj8g==", "dev": true, "license": "MIT", "dependencies": { @@ -4418,9 +4434,9 @@ } }, "node_modules/eslint/node_modules/minimatch": { - "version": "3.1.2", - "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.2.tgz", - "integrity": "sha512-J7p63hRiAjw1NDEww1W7i37+ByIrOWO5XQQAzZ3VOcL0PNybwpfmV/N05zFAzwQ9USyEcX6t3UO+K5aqBQOIHw==", + "version": "3.1.5", + "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.5.tgz", + "integrity": "sha512-VgjWUsnnT6n+NUk6eZq77zeFdpW2LWDzP6zFGrCbHXiYNul5Dzqk2HHQ5uFH2DNW5Xbp8+jVzaeNt94ssEEl4w==", "dev": true, "license": "ISC", "dependencies": { @@ -4660,9 +4676,9 @@ } }, "node_modules/flatted": { - "version": "3.3.3", - "resolved": "https://registry.npmjs.org/flatted/-/flatted-3.3.3.tgz", - "integrity": "sha512-GX+ysw4PBCz0PzosHDepZGANEuFCMLrnRTiEy9McGjmkCQYwRq4A/X786G/fjM/+OjsWSU1ZrY5qyARZmO/uwg==", + "version": "3.4.2", + "resolved": "https://registry.npmjs.org/flatted/-/flatted-3.4.2.tgz", + "integrity": "sha512-PjDse7RzhcPkIJwy5t7KPWQSZ9cAbzQXcafsetQoD7sOJRQlGikNbx7yZp2OotDnJyrDcbyRq3Ttb18iYOqkxA==", "dev": true, "license": "ISC" }, @@ -4831,7 +4847,7 @@ "version": "7.2.3", "resolved": "https://registry.npmjs.org/glob/-/glob-7.2.3.tgz", "integrity": "sha512-nFR0zLpU2YCaRxwoCJvL6UvCH2JFyFVIvwTLsIf21AuHlMskA1hhTdk+LlYJtOlYt9v6dvszD2BGRqBL+iQK9Q==", - "deprecated": "Glob versions prior to v9 are no longer supported", + "deprecated": "Old versions of glob are not supported, and contain widely publicized security vulnerabilities, which have been fixed in the current version. Please update. Support for old versions may be purchased (at exorbitant rates) by contacting i@izs.me", "dev": true, "license": "ISC", "dependencies": { @@ -4870,9 +4886,9 @@ "license": "BSD-2-Clause" }, "node_modules/glob/node_modules/brace-expansion": { - "version": "1.1.12", - "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.12.tgz", - "integrity": "sha512-9T9UjW3r0UW5c1Q7GTwllptXwhvYmEzFhzMfZ9H7FQWt+uZePjZPjBP/W1ZEyZ1twGWom5/56TF4lPcqjnDHcg==", + "version": "1.1.14", + "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-1.1.14.tgz", + "integrity": "sha512-MWPGfDxnyzKU7rNOW9SP/c50vi3xrmrua/+6hfPbCS2ABNWfx24vPidzvC7krjU/RTo235sV776ymlsMtGKj8g==", "dev": true, "license": "MIT", "dependencies": { @@ -4881,9 +4897,9 @@ } }, "node_modules/glob/node_modules/minimatch": { - "version": "3.1.2", - "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.2.tgz", - "integrity": "sha512-J7p63hRiAjw1NDEww1W7i37+ByIrOWO5XQQAzZ3VOcL0PNybwpfmV/N05zFAzwQ9USyEcX6t3UO+K5aqBQOIHw==", + "version": "3.1.5", + "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-3.1.5.tgz", + "integrity": "sha512-VgjWUsnnT6n+NUk6eZq77zeFdpW2LWDzP6zFGrCbHXiYNul5Dzqk2HHQ5uFH2DNW5Xbp8+jVzaeNt94ssEEl4w==", "dev": true, "license": "ISC", "dependencies": { @@ -5331,16 +5347,6 @@ "url": "https://github.com/sponsors/ljharb" } }, - "node_modules/is-fullwidth-code-point": { - "version": "3.0.0", - "resolved": "https://registry.npmjs.org/is-fullwidth-code-point/-/is-fullwidth-code-point-3.0.0.tgz", - "integrity": "sha512-zymm5+u+sCsSWyD9qNaejV3DFvhCKclKdizYaJUuHA83RLjb7nSuGnddCHGv0hk+KY7BMAlsWeK4Ueg6EV6XQg==", - "dev": true, - "license": "MIT", - "engines": { - "node": ">=8" - } - }, "node_modules/is-generator-function": { "version": "1.1.0", "resolved": "https://registry.npmjs.org/is-generator-function/-/is-generator-function-1.1.0.tgz", @@ -5640,13 +5646,13 @@ } }, "node_modules/jackspeak": { - "version": "4.1.1", - "resolved": "https://registry.npmjs.org/jackspeak/-/jackspeak-4.1.1.tgz", - "integrity": "sha512-zptv57P3GpL+O0I7VdMJNBZCu+BPHVQUk55Ft8/QCJjTVxrnJHuVuX/0Bl2A6/+2oyR/ZMEuFKwmzqqZ/U5nPQ==", + "version": "4.2.3", + "resolved": "https://registry.npmjs.org/jackspeak/-/jackspeak-4.2.3.tgz", + "integrity": "sha512-ykkVRwrYvFm1nb2AJfKKYPr0emF6IiXDYUaFx4Zn9ZuIH7MrzEZ3sD5RlqGXNRpHtvUHJyOnCEFxOlNDtGo7wg==", "dev": true, "license": "BlueOak-1.0.0", "dependencies": { - "@isaacs/cliui": "^8.0.2" + "@isaacs/cliui": "^9.0.0" }, "engines": { "node": "20 || >=22" @@ -5693,9 +5699,9 @@ "license": "MIT" }, "node_modules/js-yaml": { - "version": "4.1.0", - "resolved": "https://registry.npmjs.org/js-yaml/-/js-yaml-4.1.0.tgz", - "integrity": "sha512-wpxZs9NoxZaJESJGIZTyDEaYpl0FKSA+FB9aJiyemKhMwkxQg63h4T1KJgUGHpTqPDNRcmmYLugrRjJlBtWvRA==", + "version": "4.1.1", + "resolved": "https://registry.npmjs.org/js-yaml/-/js-yaml-4.1.1.tgz", + "integrity": "sha512-qQKT4zQxXl8lLwBtHMWwaTcGfFOZviOJet3Oy/xmGk2gZH677CJM9EvtfdSkgWcATZhj/55JZ0rmy3myCT5lsA==", "dev": true, "license": "MIT", "dependencies": { @@ -5807,7 +5813,8 @@ "node_modules/leaflet": { "version": "1.9.4", "resolved": "https://registry.npmjs.org/leaflet/-/leaflet-1.9.4.tgz", - "integrity": "sha512-nxS1ynzJOmOlHp+iL3FyWqK89GtNL8U8rvlMOsQdTTssxZwCXh8N2NB3GDQOL+YR3XnWyZAxwQixURb+FA74PA==" + "integrity": "sha512-nxS1ynzJOmOlHp+iL3FyWqK89GtNL8U8rvlMOsQdTTssxZwCXh8N2NB3GDQOL+YR3XnWyZAxwQixURb+FA74PA==", + "peer": true }, "node_modules/levn": { "version": "0.4.1", @@ -5907,11 +5914,11 @@ } }, "node_modules/lru-cache": { - "version": "11.1.0", - "resolved": "https://registry.npmjs.org/lru-cache/-/lru-cache-11.1.0.tgz", - "integrity": "sha512-QIXZUBJUx+2zHUdQujWejBkcD9+cs94tLn0+YL8UrCh+D5sCXZ4c7LaEH48pNwRY3MLDgqUFyhlCyjJPf1WP0A==", + "version": "11.3.6", + "resolved": "https://registry.npmjs.org/lru-cache/-/lru-cache-11.3.6.tgz", + "integrity": "sha512-Gf/KoL3C/MlI7Bt0PGI9I+TeTC/I6r/csU58N4BSNc4lppLBeKsOdFYkK+dX0ABDUMJNfCHTyPpzwwO21Awd3A==", "dev": true, - "license": "ISC", + "license": "BlueOak-1.0.0", "engines": { "node": "20 || >=22" } @@ -5981,13 +5988,13 @@ } }, "node_modules/minimatch": { - "version": "9.0.5", - "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-9.0.5.tgz", - "integrity": "sha512-G6T0ZX48xgozx7587koeX9Ys2NYy6Gmv//P89sEte9V9whIapMNF4idKxnW2QtCcLiTWlb/wfCabAtAFWhhBow==", + "version": "9.0.9", + "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-9.0.9.tgz", + "integrity": "sha512-OBwBN9AL4dqmETlpS2zasx+vTeWclWzkblfZk7KTA5j3jeOONz/tRCnZomUyvNg83wL5Zv9Ss6HMJXAgL8R2Yg==", "dev": true, "license": "ISC", "dependencies": { - "brace-expansion": "^2.0.1" + "brace-expansion": "^2.0.2" }, "engines": { "node": ">=16 || 14 >=14.17" @@ -6007,11 +6014,11 @@ } }, "node_modules/minipass": { - "version": "7.1.2", - "resolved": "https://registry.npmjs.org/minipass/-/minipass-7.1.2.tgz", - "integrity": "sha512-qOOzS1cBTWYF4BH8fVePDBOO9iptMnGUEZwNc/cMWnTV2nVLZ7VoNWEPHkYczZA0pdoA7dl6e7FL659nX9S2aw==", + "version": "7.1.3", + "resolved": "https://registry.npmjs.org/minipass/-/minipass-7.1.3.tgz", + "integrity": "sha512-tEBHqDnIoM/1rXME1zgka9g6Q2lcoCkxHLuc7ODJ5BxbP5d4c2Z5cGgtXAku59200Cx7diuHTOYfSBD8n6mm8A==", "dev": true, - "license": "ISC", + "license": "BlueOak-1.0.0", "engines": { "node": ">=16 || 14 >=14.17" } @@ -6397,9 +6404,9 @@ "license": "MIT" }, "node_modules/path-scurry": { - "version": "2.0.0", - "resolved": "https://registry.npmjs.org/path-scurry/-/path-scurry-2.0.0.tgz", - "integrity": "sha512-ypGJsmGtdXUOeM5u93TyeIEfEhM6s+ljAhrk5vAvSx8uyY/02OvrZnA0YNGUrPXfpJMgI1ODd3nwz8Npx4O4cg==", + "version": "2.0.2", + "resolved": "https://registry.npmjs.org/path-scurry/-/path-scurry-2.0.2.tgz", + "integrity": "sha512-3O/iVVsJAPsOnpwWIeD+d6z/7PmqApyQePUtCndjatj/9I5LylHvt5qluFaBT3I5h3r1ejfR056c+FCv+NnNXg==", "dev": true, "license": "BlueOak-1.0.0", "dependencies": { @@ -6407,7 +6414,7 @@ "minipass": "^7.1.2" }, "engines": { - "node": "20 || >=22" + "node": "18 || 20 || >=22" }, "funding": { "url": "https://github.com/sponsors/isaacs" @@ -6421,9 +6428,9 @@ "license": "ISC" }, "node_modules/picomatch": { - "version": "2.3.1", - "resolved": "https://registry.npmjs.org/picomatch/-/picomatch-2.3.1.tgz", - "integrity": "sha512-JU3teHTNjmE2VCGFzuY8EXzCDVwEqB2a8fsIvwaStHhAWJEeVd1o1QD80CU6+ZdEXXSLbSsuLwJjkCBWqRQUVA==", + "version": "2.3.2", + "resolved": "https://registry.npmjs.org/picomatch/-/picomatch-2.3.2.tgz", + "integrity": "sha512-V7+vQEJ06Z+c5tSye8S+nHUfI51xoXIXjHQ99cQtKUkQqqO1kO/KCJUfZXuB47h/YBlDhah2H3hdUGXn8ie0oA==", "dev": true, "license": "MIT", "engines": { @@ -6477,9 +6484,9 @@ } }, "node_modules/postcss": { - "version": "8.5.6", - "resolved": "https://registry.npmjs.org/postcss/-/postcss-8.5.6.tgz", - "integrity": "sha512-3Ybi1tAuwAP9s0r1UQ2J4n5Y0G05bJkpUIO0/bI9MhwmD70S5aTWbXGBwxHrelT+XM1k6dM0pk+SwNkpTRN7Pg==", + "version": "8.5.14", + "resolved": "https://registry.npmjs.org/postcss/-/postcss-8.5.14.tgz", + "integrity": "sha512-SoSL4+OSEtR99LHFZQiJLkT59C5B1amGO1NzTwj7TT1qCUgUO6hxOvzkOYxD+vMrXBM3XJIKzokoERdqQq/Zmg==", "dev": true, "funding": [ { @@ -6495,6 +6502,7 @@ "url": "https://github.com/sponsors/ai" } ], + "license": "MIT", "dependencies": { "nanoid": "^3.3.11", "picocolors": "^1.1.1", @@ -6520,6 +6528,7 @@ "integrity": "sha512-I7AIg5boAr5R0FFtJ6rCfD+LFsWHp81dolrFD8S79U9tb8Az2nGrJncnMSnys+bpQJfRUzqs9hnA81OAA3hCuQ==", "dev": true, "license": "MIT", + "peer": true, "bin": { "prettier": "bin/prettier.cjs" }, @@ -6593,21 +6602,12 @@ ], "license": "MIT" }, - "node_modules/randombytes": { - "version": "2.1.0", - "resolved": "https://registry.npmjs.org/randombytes/-/randombytes-2.1.0.tgz", - "integrity": "sha512-vYl3iOX+4CKUWuxGi9Ukhie6fsqXqS9FE2Zaic4tNFD2N2QQaXOMFbuKK4QmDHC0JO6B1Zp41J0LpT0oR68amQ==", - "dev": true, - "license": "MIT", - "dependencies": { - "safe-buffer": "^5.1.0" - } - }, "node_modules/react": { "version": "18.3.1", "resolved": "https://registry.npmjs.org/react/-/react-18.3.1.tgz", "integrity": "sha512-wS+hAgJShR0KhEvPJArfuPVN1+Hz1t0Y6n5jLrGQbkb4urgPE/0Rve+1kMB1v/oWgHgm4WIcV+i7F2pTVj+2iQ==", "license": "MIT", + "peer": true, "dependencies": { "loose-envify": "^1.1.0" }, @@ -6620,6 +6620,7 @@ "resolved": "https://registry.npmjs.org/react-dom/-/react-dom-18.3.1.tgz", "integrity": "sha512-5m4nQKp+rZRb09LNH59GM4BxTh9251/ylbKIbpe7TpGxfJ+9kv6BLkLBXIjjspbgbnIBNqlI23tRnTWT0snUIw==", "license": "MIT", + "peer": true, "dependencies": { "loose-envify": "^1.1.0", "scheduler": "^0.23.2" @@ -6802,16 +6803,40 @@ "url": "https://github.com/sponsors/isaacs" } }, + "node_modules/rimraf/node_modules/balanced-match": { + "version": "4.0.4", + "resolved": "https://registry.npmjs.org/balanced-match/-/balanced-match-4.0.4.tgz", + "integrity": "sha512-BLrgEcRTwX2o6gGxGOCNyMvGSp35YofuYzw9h1IMTRmKqttAZZVU67bdb9Pr2vUHA8+j3i2tJfjO6C6+4myGTA==", + "dev": true, + "license": "MIT", + "engines": { + "node": "18 || 20 || >=22" + } + }, + "node_modules/rimraf/node_modules/brace-expansion": { + "version": "5.0.5", + "resolved": "https://registry.npmjs.org/brace-expansion/-/brace-expansion-5.0.5.tgz", + "integrity": "sha512-VZznLgtwhn+Mact9tfiwx64fA9erHH/MCXEUfB/0bX/6Fz6ny5EGTXYltMocqg4xFAQZtnO3DHWWXi8RiuN7cQ==", + "dev": true, + "license": "MIT", + "dependencies": { + "balanced-match": "^4.0.2" + }, + "engines": { + "node": "18 || 20 || >=22" + } + }, "node_modules/rimraf/node_modules/glob": { - "version": "11.0.3", - "resolved": "https://registry.npmjs.org/glob/-/glob-11.0.3.tgz", - "integrity": "sha512-2Nim7dha1KVkaiF4q6Dj+ngPPMdfvLJEOpZk/jKiUAkqKebpGAWQXAq9z1xu9HKu5lWfqw/FASuccEjyznjPaA==", + "version": "11.1.0", + "resolved": "https://registry.npmjs.org/glob/-/glob-11.1.0.tgz", + "integrity": "sha512-vuNwKSaKiqm7g0THUBu2x7ckSs3XJLXE+2ssL7/MfTGPLLcrJQ/4Uq1CjPTtO5cCIiRxqvN6Twy1qOwhL0Xjcw==", + "deprecated": "Old versions of glob are not supported, and contain widely publicized security vulnerabilities, which have been fixed in the current version. Please update. Support for old versions may be purchased (at exorbitant rates) by contacting i@izs.me", "dev": true, - "license": "ISC", + "license": "BlueOak-1.0.0", "dependencies": { "foreground-child": "^3.3.1", "jackspeak": "^4.1.1", - "minimatch": "^10.0.3", + "minimatch": "^10.1.1", "minipass": "^7.1.2", "package-json-from-dist": "^1.0.0", "path-scurry": "^2.0.0" @@ -6827,16 +6852,16 @@ } }, "node_modules/rimraf/node_modules/minimatch": { - "version": "10.0.3", - "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-10.0.3.tgz", - "integrity": "sha512-IPZ167aShDZZUMdRk66cyQAW3qr0WzbHkPdMYa8bzZhlHhO3jALbKdxcaak7W9FfT2rZNpQuUu4Od7ILEpXSaw==", + "version": "10.2.5", + "resolved": "https://registry.npmjs.org/minimatch/-/minimatch-10.2.5.tgz", + "integrity": "sha512-MULkVLfKGYDFYejP07QOurDLLQpcjk7Fw+7jXS2R2czRQzR56yHRveU5NDJEOviH+hETZKSkIk5c+T23GjFUMg==", "dev": true, - "license": "ISC", + "license": "BlueOak-1.0.0", "dependencies": { - "@isaacs/brace-expansion": "^5.0.0" + "brace-expansion": "^5.0.5" }, "engines": { - "node": "20 || >=22" + "node": "18 || 20 || >=22" }, "funding": { "url": "https://github.com/sponsors/isaacs" @@ -6849,10 +6874,11 @@ "license": "Unlicense" }, "node_modules/rollup": { - "version": "4.54.0", - "resolved": "https://registry.npmjs.org/rollup/-/rollup-4.54.0.tgz", - "integrity": "sha512-3nk8Y3a9Ea8szgKhinMlGMhGMw89mqule3KWczxhIzqudyHdCIOHw8WJlj/r329fACjKLEh13ZSk7oE22kyeIw==", + "version": "4.60.3", + "resolved": "https://registry.npmjs.org/rollup/-/rollup-4.60.3.tgz", + "integrity": "sha512-pAQK9HalE84QSm4Po3EmWIZPd3FnjkShVkiMlz1iligWYkWQ7wHYd1PF/T7QZ5TVSD6uSTon5gBVMSM4JfBV+A==", "dev": true, + "license": "MIT", "dependencies": { "@types/estree": "1.0.8" }, @@ -6864,28 +6890,31 @@ "npm": ">=8.0.0" }, "optionalDependencies": { - "@rollup/rollup-android-arm-eabi": "4.54.0", - "@rollup/rollup-android-arm64": "4.54.0", - "@rollup/rollup-darwin-arm64": "4.54.0", - "@rollup/rollup-darwin-x64": "4.54.0", - "@rollup/rollup-freebsd-arm64": "4.54.0", - "@rollup/rollup-freebsd-x64": "4.54.0", - "@rollup/rollup-linux-arm-gnueabihf": "4.54.0", - "@rollup/rollup-linux-arm-musleabihf": "4.54.0", - "@rollup/rollup-linux-arm64-gnu": "4.54.0", - "@rollup/rollup-linux-arm64-musl": "4.54.0", - "@rollup/rollup-linux-loong64-gnu": "4.54.0", - "@rollup/rollup-linux-ppc64-gnu": "4.54.0", - "@rollup/rollup-linux-riscv64-gnu": "4.54.0", - "@rollup/rollup-linux-riscv64-musl": "4.54.0", - "@rollup/rollup-linux-s390x-gnu": "4.54.0", - "@rollup/rollup-linux-x64-gnu": "4.54.0", - "@rollup/rollup-linux-x64-musl": "4.54.0", - "@rollup/rollup-openharmony-arm64": "4.54.0", - "@rollup/rollup-win32-arm64-msvc": "4.54.0", - "@rollup/rollup-win32-ia32-msvc": "4.54.0", - "@rollup/rollup-win32-x64-gnu": "4.54.0", - "@rollup/rollup-win32-x64-msvc": "4.54.0", + "@rollup/rollup-android-arm-eabi": "4.60.3", + "@rollup/rollup-android-arm64": "4.60.3", + "@rollup/rollup-darwin-arm64": "4.60.3", + "@rollup/rollup-darwin-x64": "4.60.3", + "@rollup/rollup-freebsd-arm64": "4.60.3", + "@rollup/rollup-freebsd-x64": "4.60.3", + "@rollup/rollup-linux-arm-gnueabihf": "4.60.3", + "@rollup/rollup-linux-arm-musleabihf": "4.60.3", + "@rollup/rollup-linux-arm64-gnu": "4.60.3", + "@rollup/rollup-linux-arm64-musl": "4.60.3", + "@rollup/rollup-linux-loong64-gnu": "4.60.3", + "@rollup/rollup-linux-loong64-musl": "4.60.3", + "@rollup/rollup-linux-ppc64-gnu": "4.60.3", + "@rollup/rollup-linux-ppc64-musl": "4.60.3", + "@rollup/rollup-linux-riscv64-gnu": "4.60.3", + "@rollup/rollup-linux-riscv64-musl": "4.60.3", + "@rollup/rollup-linux-s390x-gnu": "4.60.3", + "@rollup/rollup-linux-x64-gnu": "4.60.3", + "@rollup/rollup-linux-x64-musl": "4.60.3", + "@rollup/rollup-openbsd-x64": "4.60.3", + "@rollup/rollup-openharmony-arm64": "4.60.3", + "@rollup/rollup-win32-arm64-msvc": "4.60.3", + "@rollup/rollup-win32-ia32-msvc": "4.60.3", + "@rollup/rollup-win32-x64-gnu": "4.60.3", + "@rollup/rollup-win32-x64-msvc": "4.60.3", "fsevents": "~2.3.2" } }, @@ -7052,16 +7081,6 @@ "node": ">=10" } }, - "node_modules/serialize-javascript": { - "version": "6.0.2", - "resolved": "https://registry.npmjs.org/serialize-javascript/-/serialize-javascript-6.0.2.tgz", - "integrity": "sha512-Saa1xPByTTq2gdeFZYLLo+RFE35NHZkAbqZeWNd3BpzppeVisAqpDjcp8dyf6uIvEqJRd46jemmyA4iFIeVk8g==", - "dev": true, - "license": "BSD-3-Clause", - "dependencies": { - "randombytes": "^2.1.0" - } - }, "node_modules/set-function-length": { "version": "1.2.2", "resolved": "https://registry.npmjs.org/set-function-length/-/set-function-length-1.2.2.tgz", @@ -7263,35 +7282,18 @@ } }, "node_modules/socket.io-parser": { - "version": "4.2.4", - "resolved": "https://registry.npmjs.org/socket.io-parser/-/socket.io-parser-4.2.4.tgz", - "integrity": "sha512-/GbIKmo8ioc+NIWIhwdecY0ge+qVBSMdgxGygevmdHj24bsfgtCmcUUcQ5ZzcylGFHsN3k4HB4Cgkl96KVnuew==", + "version": "4.2.6", + "resolved": "https://registry.npmjs.org/socket.io-parser/-/socket.io-parser-4.2.6.tgz", + "integrity": "sha512-asJqbVBDsBCJx0pTqw3WfesSY0iRX+2xzWEWzrpcH7L6fLzrhyF8WPI8UaeM4YCuDfpwA/cgsdugMsmtz8EJeg==", "license": "MIT", "dependencies": { "@socket.io/component-emitter": "~3.1.0", - "debug": "~4.3.1" + "debug": "~4.4.1" }, "engines": { "node": ">=10.0.0" } }, - "node_modules/socket.io-parser/node_modules/debug": { - "version": "4.3.7", - "resolved": "https://registry.npmjs.org/debug/-/debug-4.3.7.tgz", - "integrity": "sha512-Er2nc/H7RrMXZBFCEim6TCmMk02Z8vLC2Rbi1KEBggpo0fS6l0S1nnapwmIi3yW/+GOJap1Krg4w0Hg80oCqgQ==", - "license": "MIT", - "dependencies": { - "ms": "^2.1.3" - }, - "engines": { - "node": ">=6.0" - }, - "peerDependenciesMeta": { - "supports-color": { - "optional": true - } - } - }, "node_modules/source-map": { "version": "0.7.6", "resolved": "https://registry.npmjs.org/source-map/-/source-map-0.7.6.tgz", @@ -7356,70 +7358,6 @@ "safe-buffer": "~5.1.0" } }, - "node_modules/string-width": { - "version": "5.1.2", - "resolved": "https://registry.npmjs.org/string-width/-/string-width-5.1.2.tgz", - "integrity": "sha512-HnLOCR3vjcY8beoNLtcjZ5/nxn2afmME6lhrDrebokqMap+XbeW8n9TXpPDOqdGK5qcI3oT0GKTW6wC7EMiVqA==", - "dev": true, - "license": "MIT", - "dependencies": { - "eastasianwidth": "^0.2.0", - "emoji-regex": "^9.2.2", - "strip-ansi": "^7.0.1" - }, - "engines": { - "node": ">=12" - }, - "funding": { - "url": "https://github.com/sponsors/sindresorhus" - } - }, - "node_modules/string-width-cjs": { - "name": "string-width", - "version": "4.2.3", - "resolved": "https://registry.npmjs.org/string-width/-/string-width-4.2.3.tgz", - "integrity": "sha512-wKyQRQpjJ0sIp62ErSZdGsjMJWsap5oRNihHhu6G7JVO/9jIB6UyevL+tXuOqrng8j/cxKTWyWUwvSTriiZz/g==", - "dev": true, - "license": "MIT", - "dependencies": { - "emoji-regex": "^8.0.0", - "is-fullwidth-code-point": "^3.0.0", - "strip-ansi": "^6.0.1" - }, - "engines": { - "node": ">=8" - } - }, - "node_modules/string-width-cjs/node_modules/ansi-regex": { - "version": "5.0.1", - "resolved": "https://registry.npmjs.org/ansi-regex/-/ansi-regex-5.0.1.tgz", - "integrity": "sha512-quJQXlTSUGL2LH9SUXo8VwsY4soanhgo6LNSm84E1LBcE8s3O0wpdiRzyR9z/ZZJMlMWv37qOOb9pdJlMUEKFQ==", - "dev": true, - "license": "MIT", - "engines": { - "node": ">=8" - } - }, - "node_modules/string-width-cjs/node_modules/emoji-regex": { - "version": "8.0.0", - "resolved": "https://registry.npmjs.org/emoji-regex/-/emoji-regex-8.0.0.tgz", - "integrity": "sha512-MSjYzcWNOA0ewAHpz0MxpYFvwg6yjy1NG3xteoqz644VCo/RPgnr1/GGt+ic3iJTzQ8Eu3TdM14SawnVUmGE6A==", - "dev": true, - "license": "MIT" - }, - "node_modules/string-width-cjs/node_modules/strip-ansi": { - "version": "6.0.1", - "resolved": "https://registry.npmjs.org/strip-ansi/-/strip-ansi-6.0.1.tgz", - "integrity": "sha512-Y38VPSHcqkFrCpFnQ9vuSXmquuv5oXOKpGeT6aGrr3o3Gc9AlVa6JBfUSOCnbxGGZF+/0ooI7KrPuUSztUdU5A==", - "dev": true, - "license": "MIT", - "dependencies": { - "ansi-regex": "^5.0.1" - }, - "engines": { - "node": ">=8" - } - }, "node_modules/string.prototype.matchall": { "version": "4.0.12", "resolved": "https://registry.npmjs.org/string.prototype.matchall/-/string.prototype.matchall-4.0.12.tgz", @@ -7518,46 +7456,6 @@ "url": "https://github.com/sponsors/ljharb" } }, - "node_modules/strip-ansi": { - "version": "7.1.0", - "resolved": "https://registry.npmjs.org/strip-ansi/-/strip-ansi-7.1.0.tgz", - "integrity": "sha512-iq6eVVI64nQQTRYq2KtEg2d2uU7LElhTJwsH4YzIHZshxlgZms/wIc4VoDQTlG/IvVIrBKG06CrZnp0qv7hkcQ==", - "dev": true, - "license": "MIT", - "dependencies": { - "ansi-regex": "^6.0.1" - }, - "engines": { - "node": ">=12" - }, - "funding": { - "url": "https://github.com/chalk/strip-ansi?sponsor=1" - } - }, - "node_modules/strip-ansi-cjs": { - "name": "strip-ansi", - "version": "6.0.1", - "resolved": "https://registry.npmjs.org/strip-ansi/-/strip-ansi-6.0.1.tgz", - "integrity": "sha512-Y38VPSHcqkFrCpFnQ9vuSXmquuv5oXOKpGeT6aGrr3o3Gc9AlVa6JBfUSOCnbxGGZF+/0ooI7KrPuUSztUdU5A==", - "dev": true, - "license": "MIT", - "dependencies": { - "ansi-regex": "^5.0.1" - }, - "engines": { - "node": ">=8" - } - }, - "node_modules/strip-ansi-cjs/node_modules/ansi-regex": { - "version": "5.0.1", - "resolved": "https://registry.npmjs.org/ansi-regex/-/ansi-regex-5.0.1.tgz", - "integrity": "sha512-quJQXlTSUGL2LH9SUXo8VwsY4soanhgo6LNSm84E1LBcE8s3O0wpdiRzyR9z/ZZJMlMWv37qOOb9pdJlMUEKFQ==", - "dev": true, - "license": "MIT", - "engines": { - "node": ">=8" - } - }, "node_modules/strip-bom": { "version": "3.0.0", "resolved": "https://registry.npmjs.org/strip-bom/-/strip-bom-3.0.0.tgz", @@ -7657,16 +7555,15 @@ } }, "node_modules/terser-webpack-plugin": { - "version": "5.3.14", - "resolved": "https://registry.npmjs.org/terser-webpack-plugin/-/terser-webpack-plugin-5.3.14.tgz", - "integrity": "sha512-vkZjpUjb6OMS7dhV+tILUW6BhpDR7P2L/aQSAv+Uwk+m8KATX9EccViHTJR2qDtACKPIYndLGCyl3FMo+r2LMw==", + "version": "5.5.0", + "resolved": "https://registry.npmjs.org/terser-webpack-plugin/-/terser-webpack-plugin-5.5.0.tgz", + "integrity": "sha512-UYhptBwhWvfIjKd/UuFo6D8uq9xpGLDK+z8EDsj/zWhrTaH34cKEbrkMKfV5YWqGBvAYA3tlzZbs2R+qYrbQJA==", "dev": true, "license": "MIT", "dependencies": { "@jridgewell/trace-mapping": "^0.3.25", "jest-worker": "^27.4.5", "schema-utils": "^4.3.0", - "serialize-javascript": "^6.0.2", "terser": "^5.31.1" }, "engines": { @@ -7692,11 +7589,12 @@ } }, "node_modules/terser-webpack-plugin/node_modules/ajv": { - "version": "8.17.1", - "resolved": "https://registry.npmjs.org/ajv/-/ajv-8.17.1.tgz", - "integrity": "sha512-B/gBuNg5SiMTrPkC+A2+cW0RszwxYmn6VYxB/inlBStS5nx6xHIt/ehKRhIMhqusl7a8LjQoZnjCs5vhwxOQ1g==", + "version": "8.20.0", + "resolved": "https://registry.npmjs.org/ajv/-/ajv-8.20.0.tgz", + "integrity": "sha512-Thbli+OlOj+iMPYFBVBfJ3OmCAnaSyNn4M1vz9T6Gka5Jt9ba/HIR56joy65tY6kx/FCF5VXNB819Y7/GUrBGA==", "dev": true, "license": "MIT", + "peer": true, "dependencies": { "fast-deep-equal": "^3.1.3", "fast-uri": "^3.0.1", @@ -7789,10 +7687,12 @@ } }, "node_modules/tinyglobby/node_modules/picomatch": { - "version": "4.0.3", - "resolved": "https://registry.npmjs.org/picomatch/-/picomatch-4.0.3.tgz", - "integrity": "sha512-5gTmgEY/sqK6gFXLIsQNH19lWb4ebPDLA4SdLP7dsWkIXHWlG66oPuVvXSGFPppYZz8ZDZq0dYYrbHfBCVUb1Q==", + "version": "4.0.4", + "resolved": "https://registry.npmjs.org/picomatch/-/picomatch-4.0.4.tgz", + "integrity": "sha512-QP88BAKvMam/3NxH6vj2o21R6MjxZUAd6nlwAS/pnGvN9IVLocLHxGYIzFhg6fUQ+5th6P4dv4eW9jX3DSIj7A==", "dev": true, + "license": "MIT", + "peer": true, "engines": { "node": ">=12" }, @@ -7997,6 +7897,7 @@ "integrity": "sha512-CWBzXQrc/qOkhidw1OzBTQuYRbfyxDXJMVJ1XNwUHGROVmuaeiEm3OslpZ1RV96d7SKKjZKrSJu3+t/xlw3R9A==", "dev": true, "license": "Apache-2.0", + "peer": true, "bin": { "tsc": "bin/tsc", "tsserver": "bin/tsserver" @@ -8111,10 +8012,12 @@ "license": "MIT" }, "node_modules/vite": { - "version": "6.4.1", - "resolved": "https://registry.npmjs.org/vite/-/vite-6.4.1.tgz", - "integrity": "sha512-+Oxm7q9hDoLMyJOYfUYBuHQo+dkAloi33apOPP56pzj+vsdJDzr+j1NISE5pyaAuKL4A3UD34qd0lx5+kfKp2g==", + "version": "6.4.2", + "resolved": "https://registry.npmjs.org/vite/-/vite-6.4.2.tgz", + "integrity": "sha512-2N/55r4JDJ4gdrCvGgINMy+HH3iRpNIz8K6SFwVsA+JbQScLiC+clmAxBgwiSPgcG9U15QmvqCGWzMbqda5zGQ==", "dev": true, + "license": "MIT", + "peer": true, "dependencies": { "esbuild": "^0.25.0", "fdir": "^6.4.4", @@ -8202,10 +8105,12 @@ } }, "node_modules/vite/node_modules/picomatch": { - "version": "4.0.3", - "resolved": "https://registry.npmjs.org/picomatch/-/picomatch-4.0.3.tgz", - "integrity": "sha512-5gTmgEY/sqK6gFXLIsQNH19lWb4ebPDLA4SdLP7dsWkIXHWlG66oPuVvXSGFPppYZz8ZDZq0dYYrbHfBCVUb1Q==", + "version": "4.0.4", + "resolved": "https://registry.npmjs.org/picomatch/-/picomatch-4.0.4.tgz", + "integrity": "sha512-QP88BAKvMam/3NxH6vj2o21R6MjxZUAd6nlwAS/pnGvN9IVLocLHxGYIzFhg6fUQ+5th6P4dv4eW9jX3DSIj7A==", "dev": true, + "license": "MIT", + "peer": true, "engines": { "node": ">=12" }, @@ -8240,6 +8145,7 @@ "integrity": "sha512-l2LlBSvVZGhL4ZrPwyr8+37AunkcYj5qh8o6u2/2rzoPc8gxFJkLj1WxNgooi9pnoc06jh0BjuXnamM4qlujZA==", "dev": true, "license": "MIT", + "peer": true, "dependencies": { "@types/eslint-scope": "^3.7.7", "@types/estree": "^1.0.6", @@ -8448,101 +8354,6 @@ "node": ">=0.10.0" } }, - "node_modules/wrap-ansi": { - "version": "8.1.0", - "resolved": "https://registry.npmjs.org/wrap-ansi/-/wrap-ansi-8.1.0.tgz", - "integrity": "sha512-si7QWI6zUMq56bESFvagtmzMdGOtoxfR+Sez11Mobfc7tm+VkUckk9bW2UeffTGVUbOksxmSw0AA2gs8g71NCQ==", - "dev": true, - "license": "MIT", - "dependencies": { - "ansi-styles": "^6.1.0", - "string-width": "^5.0.1", - "strip-ansi": "^7.0.1" - }, - "engines": { - "node": ">=12" - }, - "funding": { - "url": "https://github.com/chalk/wrap-ansi?sponsor=1" - } - }, - "node_modules/wrap-ansi-cjs": { - "name": "wrap-ansi", - "version": "7.0.0", - "resolved": "https://registry.npmjs.org/wrap-ansi/-/wrap-ansi-7.0.0.tgz", - "integrity": "sha512-YVGIj2kamLSTxw6NsZjoBxfSwsn0ycdesmc4p+Q21c5zPuZ1pl+NfxVdxPtdHvmNVOQ6XSYG4AUtyt/Fi7D16Q==", - "dev": true, - "license": "MIT", - "dependencies": { - "ansi-styles": "^4.0.0", - "string-width": "^4.1.0", - "strip-ansi": "^6.0.0" - }, - "engines": { - "node": ">=10" - }, - "funding": { - "url": "https://github.com/chalk/wrap-ansi?sponsor=1" - } - }, - "node_modules/wrap-ansi-cjs/node_modules/ansi-regex": { - "version": "5.0.1", - "resolved": "https://registry.npmjs.org/ansi-regex/-/ansi-regex-5.0.1.tgz", - "integrity": "sha512-quJQXlTSUGL2LH9SUXo8VwsY4soanhgo6LNSm84E1LBcE8s3O0wpdiRzyR9z/ZZJMlMWv37qOOb9pdJlMUEKFQ==", - "dev": true, - "license": "MIT", - "engines": { - "node": ">=8" - } - }, - "node_modules/wrap-ansi-cjs/node_modules/emoji-regex": { - "version": "8.0.0", - "resolved": "https://registry.npmjs.org/emoji-regex/-/emoji-regex-8.0.0.tgz", - "integrity": "sha512-MSjYzcWNOA0ewAHpz0MxpYFvwg6yjy1NG3xteoqz644VCo/RPgnr1/GGt+ic3iJTzQ8Eu3TdM14SawnVUmGE6A==", - "dev": true, - "license": "MIT" - }, - "node_modules/wrap-ansi-cjs/node_modules/string-width": { - "version": "4.2.3", - "resolved": "https://registry.npmjs.org/string-width/-/string-width-4.2.3.tgz", - "integrity": "sha512-wKyQRQpjJ0sIp62ErSZdGsjMJWsap5oRNihHhu6G7JVO/9jIB6UyevL+tXuOqrng8j/cxKTWyWUwvSTriiZz/g==", - "dev": true, - "license": "MIT", - "dependencies": { - "emoji-regex": "^8.0.0", - "is-fullwidth-code-point": "^3.0.0", - "strip-ansi": "^6.0.1" - }, - "engines": { - "node": ">=8" - } - }, - "node_modules/wrap-ansi-cjs/node_modules/strip-ansi": { - "version": "6.0.1", - "resolved": "https://registry.npmjs.org/strip-ansi/-/strip-ansi-6.0.1.tgz", - "integrity": "sha512-Y38VPSHcqkFrCpFnQ9vuSXmquuv5oXOKpGeT6aGrr3o3Gc9AlVa6JBfUSOCnbxGGZF+/0ooI7KrPuUSztUdU5A==", - "dev": true, - "license": "MIT", - "dependencies": { - "ansi-regex": "^5.0.1" - }, - "engines": { - "node": ">=8" - } - }, - "node_modules/wrap-ansi/node_modules/ansi-styles": { - "version": "6.2.1", - "resolved": "https://registry.npmjs.org/ansi-styles/-/ansi-styles-6.2.1.tgz", - "integrity": "sha512-bN798gFfQX+viw3R7yrGWRqnrN2oRkEkUjjl4JNn4E8GxxbjtG3FbrEIIY3l8/hrwUwIeCZvi4QuOTP4MErVug==", - "dev": true, - "license": "MIT", - "engines": { - "node": ">=12" - }, - "funding": { - "url": "https://github.com/chalk/ansi-styles?sponsor=1" - } - }, "node_modules/wrappy": { "version": "1.0.2", "resolved": "https://registry.npmjs.org/wrappy/-/wrappy-1.0.2.tgz", diff --git a/dimos/web/command-center-extension/package.json b/dimos/web/command-center-extension/package.json index e3c1a5060f..89aef29753 100644 --- a/dimos/web/command-center-extension/package.json +++ b/dimos/web/command-center-extension/package.json @@ -30,7 +30,7 @@ "@types/react": "18.3.24", "@types/react-dom": "18.3.7", "@vitejs/plugin-react": "^4.3.4", - "create-foxglove-extension": "1.0.6", + "create-foxglove-extension": "^1.0.6", "eslint": "9.34.0", "prettier": "3.6.2", "react": "18.3.1", diff --git a/dimos/web/dimos_interface/api/README.md b/dimos/web/dimos_interface/api/README.md index 67cb855601..3be07915a7 100644 --- a/dimos/web/dimos_interface/api/README.md +++ b/dimos/web/dimos_interface/api/README.md @@ -8,10 +8,7 @@ This is a minimal FastAPI server implementation that provides API endpoints for # Navigate to the api directory cd api -# Install minimal requirements -pip install -r requirements.txt - -# Run the server +# Run the server (install the project's `web` extra first, e.g. `pip install -e '.[web]'`) python unitree_server.py ``` diff --git a/dimos/web/dimos_interface/api/requirements.txt b/dimos/web/dimos_interface/api/requirements.txt deleted file mode 100644 index a1ab33e428..0000000000 --- a/dimos/web/dimos_interface/api/requirements.txt +++ /dev/null @@ -1,7 +0,0 @@ -fastapi==0.104.1 -uvicorn==0.24.0 -reactivex==4.0.4 -numpy<2.0.0 # Specify older NumPy version for cv2 compatibility -opencv-python==4.8.1.78 -python-multipart==0.0.6 -jinja2==3.1.2 diff --git a/docs/capabilities/manipulation/openarm_integration.md b/docs/capabilities/manipulation/openarm_integration.md new file mode 100644 index 0000000000..49a78ccde7 --- /dev/null +++ b/docs/capabilities/manipulation/openarm_integration.md @@ -0,0 +1,387 @@ +# OpenArm Integration + +Guide for running the **OpenArm** — an open-source bimanual 7-DOF research arm built from Damiao DM-J quasi-direct-drive motors — under the dimos manipulation + control stack. + +**If you're standing in front of the hardware and just want to run it, skip to [Quick start](#quick-start).** + +Related: +- Upstream hardware + C++ reference: [enactic/openarm_can](https://github.com/enactic/openarm_can) +- How to integrate any new arm: [adding_a_custom_arm.md](/docs/capabilities/manipulation/adding_a_custom_arm.md) + +--- + +## Why this integration is different + +Every other arm in dimos wraps a vendor Python SDK: + +| Arm | Transport | Python SDK | +|---|---|---| +| xArm | TCP/IP | `xarm-python-sdk` | +| Piper | CAN (via SDK) | `piper_sdk` | +| R1 Pro | Galaxea | Galaxea SDK | +| Go2 / G1 | WebRTC | Unitree SDK | +| Panda | FCI | `panda-py` | + +**OpenArm ships no Python SDK.** The only interface is raw CAN frames on the wire, speaking the Damiao MIT-mode protocol. So dimos includes a from-scratch driver that encodes/decodes the protocol directly on a SocketCAN bus. The reference implementation is the Enactic C++ library at [enactic/openarm_can](https://github.com/enactic/openarm_can) — we port the frame layout from there. + +## Architecture + +``` +ManipulationModule → ControlCoordinator → OpenArmAdapter → OpenArmBus → SocketCAN → arm + (Drake plan) (100Hz tick loop) (dimos protocol) (CAN driver) +``` + +Code layout: + +``` +dimos/hardware/manipulators/openarm/ +├── driver.py # OpenArmBus, DamiaoMotor — pure CAN driver, no dimos deps +├── adapter.py # OpenArmAdapter — implements dimos ManipulatorAdapter protocol +├── test_driver.py # 13 unit tests (virtual CAN loopback, no hardware) +└── test_adapter.py # 11 unit tests (virtual CAN + mock state frames) + +dimos/robot/catalog/openarm.py # openarm_arm() and openarm_single() config factories +dimos/robot/manipulators/openarm/ +├── blueprints.py # coordinator-*, planner-*, keyboard-teleop-* blueprints +└── scripts/ # bring-up + diagnostic scripts (run manually by humans) + ├── openarm_can_up.sh # bring SocketCAN interfaces up (needs sudo) + ├── openarm_can_probe.py # enumerate & read state from all 8 motors + ├── openarm_set_mit_mode.py # one-time CTRL_MODE=MIT write per motor + └── ... (diagnostics) + +data/openarm_description/ # URDF + meshes (in-tree; may migrate to LFS) +└── urdf/robot/ + ├── openarm_v10_bimanual.urdf # both arms (14 DOF, used by coordinator) + ├── openarm_v10_left.urdf # left arm + torso (7 DOF, per-side planning) + ├── openarm_v10_right.urdf # right arm + torso (7 DOF) + └── openarm_v10_single.urdf # standalone arm (Pinocchio FK for teleop) +``` + +Workspace analysis is generic and lives in [dimos/utils/workspace.py](/dimos/utils/workspace.py) — works for any URDF, not just OpenArm. + +--- + +## Quick start + +You need: + +- 2× **OpenArm v10** arms, wired to USB-CAN adapters +- 2× **USB-CAN adapters** (we used gs_usb family, VID:PID `1d50:606f`, e.g. CANable 2.0). Classical CAN @ 1 Mbit is enough; CAN-FD not required +- **Python 3.12 venv with dimos installed** plus `python-can >= 4.3` and `pinocchio` +- **sudo** on first run (to bring up the CAN interfaces) + +### 1. Bring up the CAN buses + +```bash +sudo ./dimos/robot/manipulators/openarm/scripts/openarm_can_up.sh can0 can1 +``` + +This sets both interfaces to classical CAN @ 1 Mbit with a 1000-frame TX queue (enough headroom for the 100 Hz tick loop). If only one bus is present, pass just that one: `sudo ... openarm_can_up.sh can0`. + +**Troubleshooting:** +- `Operation not permitted` → you forgot `sudo`. +- `Operation not supported` on `fd on` → your adapter doesn't support CAN-FD. The script defaults to classical, so this shouldn't happen unless you set `MODE=fd`. +- Only one `can*` interface appears → the other adapter isn't enumerating. On gs_usb boards, the **blue LED** indicates USB enumeration. If one adapter only shows red/green, swap the USB cable (many USB-C cables are charge-only). + +### 2. Verify all 16 motors are alive + +```bash +python ./dimos/robot/manipulators/openarm/scripts/openarm_can_probe.py --channel can0 +python ./dimos/robot/manipulators/openarm/scripts/openarm_can_probe.py --channel can1 +``` + +Expected: `8/8 motors replied` on each bus, with plausible joint positions and rotor temps around 25–30 °C. + +### 3. (First time only) Put motors in MIT mode + +Damiao motors have a persistent `CTRL_MODE` register. They ship in POS_VEL mode by default, which means they will reply to enable/state queries but **silently ignore** any MIT control frames — the "motor doesn't move, error grows" failure. The adapter writes MIT on every `connect()` by default, so this step is usually automatic. If you want to set it explicitly once: + +```bash +python ./dimos/robot/manipulators/openarm/scripts/openarm_set_mit_mode.py --channel can0 +python ./dimos/robot/manipulators/openarm/scripts/openarm_set_mit_mode.py --channel can1 +``` + +The register is persistent across power cycles, so you only need this once per motor (or after a firmware reset). + +### 4. Run a blueprint + +| Blueprint | What it does | +|---|---| +| `coordinator-openarm-mock` | Bimanual, mock adapters. No hardware. | +| `openarm-mock-planner-coordinator` | Drake planner + bimanual mock, Meshcat viz. Great smoke test. | +| `coordinator-openarm-left` / `coordinator-openarm-right` | Single arm, real hardware on can0 / can1. | +| `coordinator-openarm-bimanual` | Both arms, real hardware, no planner. | +| `openarm-planner-coordinator` | **Main usable blueprint** — Drake planner + both arms on real hardware. | +| `keyboard-teleop-openarm-mock` / `keyboard-teleop-openarm` | Single-arm Cartesian IK + pygame keyboard, mock / real. | + +**Safety before hot-plugging hardware:** hold the arms before starting. On connect, the adapter enables all motors and sends gravity-comp holds — the arms go slightly stiff but don't leap. Ctrl-C to cleanly disable and exit. + +First-time recommendation: mock planner to verify everything wires up, then real single-arm, then bimanual. + +```bash +# smoke test (no hardware) +dimos run openarm-mock-planner-coordinator + +# single-arm bring-up (hold the arm physically first) +dimos run coordinator-openarm-left + +# full bimanual with planner +dimos run openarm-planner-coordinator +``` + +Meshcat will appear at http://localhost:7000. + +### 5. Drive the arms from the manipulation client + +With `openarm-planner-coordinator` running in one terminal, open a second terminal and start the REPL client: + +```bash +python -i -m dimos.manipulation.planning.examples.manipulation_client +``` + +This gives you an interactive Python prompt with these functions: + +| Function | Purpose | +|---|---| +| `robots()` | List configured robots (here: `["left_arm", "right_arm"]`) | +| `joints(robot_name)` | Read current joint positions (7 floats) | +| `ee(robot_name)` | Read current end-effector pose | +| `state()` | Module state: `IDLE`, `PLANNING`, `EXECUTING`, `FAULT`, etc. | +| `plan([q1..q7], robot_name)` | Plan a collision-free trajectory to a joint configuration | +| `plan_pose(x, y, z, robot_name=...)` | Plan to a Cartesian EE pose (preserves current orientation) | +| `preview(robot_name)` | Animate the planned path in Meshcat without executing | +| `execute(robot_name)` | Send the planned trajectory to the coordinator | +| `home(robot_name)` | Plan + execute to home joints | +| `commands()` | Print all available functions | + +#### Example session — simple joint moves + +```python +>>> robots() +['left_arm', 'right_arm'] + +>>> joints(robot_name="left_arm") +[0.02, -0.01, -0.13, 0.15, 0.17, -0.07, 0.10] + +>>> # One-liner: plan → preview in Meshcat → execute on hardware +>>> plan([0.3, 0, 0, 0, 0, 0, 0], robot_name="left_arm") and preview(robot_name="left_arm") and execute(robot_name="left_arm") +True + +>>> joints(robot_name="left_arm") +[0.30, 0.00, 0.00, 0.00, 0.00, 0.00, 0.00] # arm is now at the commanded pose +``` + +`plan()` returns `True` on success, `False` if planning failed (check the coordinator terminal for `COLLISION_AT_GOAL`, `INVALID_START`, `NO_SOLUTION`, etc). The `and` chaining is an idiom — if any step fails, the next one is short-circuited. + +If you ever get stuck in a `FAULT` state (e.g. an invalid plan was sent), reset the state machine: + +```python +>>> _client.reset() +'Reset to IDLE — ready for new commands' +``` + +#### Example session — bimanual + +```python +>>> # Move both arms to mirrored poses +>>> plan([0.5, 0, 0, 0, 0, 0, 0], robot_name="left_arm") and execute(robot_name="left_arm") +True +>>> plan([-0.5, 0, 0, 0, 0, 0, 0], robot_name="right_arm") and execute(robot_name="right_arm") +True +``` + +Each arm plans and executes independently — the coordinator runs both trajectories simultaneously on separate tick-loop tasks. + +#### Example session — Cartesian target + +```python +>>> ee(robot_name="left_arm") # see where the EE currently is +>>> plan_pose(0.1, 0.3, 0.5, robot_name="left_arm") and preview(robot_name="left_arm") +True +>>> execute(robot_name="left_arm") +True +``` + +If you don't know which Cartesian targets are reachable, check first with the workspace tool — see [Workspace analysis](#workspace-analysis) below. `plan_pose` will fail with `NO_SOLUTION` if the IK can't find a configuration reaching the target. + +#### Adding obstacles + +```python +>>> add_box("table", 0.4, 0.0, 0.1, w=0.6, h=0.4, d=0.05) # rectangular obstacle +>>> add_sphere("ball", 0.3, 0.2, 0.4, radius=0.05) +>>> plan_pose(0.4, 0.0, 0.3, robot_name="left_arm") # now plans around it +>>> remove("table") # id returned by add_* +``` + +--- + +## Configuration + +### Which CAN bus is which arm + +Linux assigns `can0`/`can1` in USB-enumeration order, which isn't guaranteed stable across reboots or cable swaps. If the arms come up "swapped" (commanding `left_arm` moves the physical right arm), flip these two constants at the top of [blueprints.py](/dimos/robot/manipulators/openarm/blueprints.py): + +```python +LEFT_CAN = "can0" +RIGHT_CAN = "can1" +``` + +No other code changes are needed. + +### Gain tuning (MIT kp/kd) + +Defaults live in [adapter.py](/dimos/hardware/manipulators/openarm/adapter.py). Gains are per-joint because the shoulder motors (DM8006, 40 Nm) tolerate higher kp than the wrist motors (DM4310, 10 Nm): + +```python +_DEFAULT_KP = [100.0, 100.0, 80.0, 80.0, 60.0, 60.0, 60.0] +_DEFAULT_KD = [1.5, 1.5, 1.0, 1.0, 0.8, 0.8, 0.8] +``` + +Guidelines: +- `kp ∈ [0, 500]` in MIT mode. Higher kp = stiffer position tracking; too high → oscillation. +- `kd ∈ [0, 5]`. Higher kd = more damping, but values above ~2 on these gearboxes cause high-frequency buzz/grinding. +- Gravity compensation is on by default (`gravity_comp=True`) — the adapter uses Pinocchio to compute `G(q)` and adds it as feedforward torque. This removes the need for very high kp to fight gravity, so prefer low kp + gravity comp over high kp. + +### Physical joint limits + +The URDFs use the xacro-generated limits (which include per-side offsets for mirroring). The adapter's `get_limits()` reports the same per-side limits. If you measure tighter physical limits and want to enforce them, edit the URDFs directly — the planner will respect them. + +### Disabling auto MIT-mode write + +The adapter writes `CTRL_MODE=MIT` to every motor at `connect()`. It's idempotent (writing the same value is a no-op), so this is safe to leave on. To verify that a previous write persisted across a power cycle, flip `AUTO_SET_MIT_MODE = False` in [blueprints.py](/dimos/robot/manipulators/openarm/blueprints.py) and restart — the arms should still respond. + +--- + +## Motor mapping (OpenArm v10) + +Derived from the URDF's `joint_limits.yaml` (effort column) cross-checked against the Damiao torque tables. Both arms are identical. + +| Send ID | Recv ID | Joint | Motor | vMax [rad/s] | tMax [Nm] | +|---|---|---|---|---|---| +| 0x01 | 0x11 | joint1 | DM8006 | 45 | 40 | +| 0x02 | 0x12 | joint2 | DM8006 | 45 | 40 | +| 0x03 | 0x13 | joint3 | DM4340 | 8 | 28 | +| 0x04 | 0x14 | joint4 | DM4340 | 8 | 28 | +| 0x05 | 0x15 | joint5 | DM4310 | 30 | 10 | +| 0x06 | 0x16 | joint6 | DM4310 | 30 | 10 | +| 0x07 | 0x17 | joint7 | DM4310 | 30 | 10 | +| 0x08 | 0x18 | gripper | DM4310 | 30 | 10 | + +Convention: `recv_id = send_id | 0x10`. + +--- + +## Damiao protocol essentials + +Ported from `enactic/openarm_can/src/openarm/damiao_motor/dm_motor_control.cpp`. You shouldn't need these unless you're modifying the driver. + +### Enable / disable / zero-position + +Send to the motor's send_id. 8-byte payload: + +``` +[0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, 0xFF, CMD] + where CMD = 0xFC (enable) | 0xFD (disable) | 0xFE (zero current pose) +``` + +### MIT control frame (8 bytes) + +Bit layout: `q[16] | dq[12] | kp[12] | kd[12] | tau[12]`. Each float quantized via: + +```python +def float_to_uint(x, lo, hi, bits): + x = clamp(x, lo, hi) + return round((x - lo) / (hi - lo) * ((1 << bits) - 1)) +``` + +Gain ranges: `kp ∈ [0, 500]`, `kd ∈ [0, 5]`. Position/velocity/torque ranges come from the motor-type table above. + +Byte layout: +``` +byte0 = q_u >> 8 +byte1 = q_u & 0xFF +byte2 = dq_u >> 4 +byte3 = ((dq_u & 0xF) << 4) | ((kp_u >> 8) & 0xF) +byte4 = kp_u & 0xFF +byte5 = kd_u >> 4 +byte6 = ((kd_u & 0xF) << 4) | ((tau_u >> 8) & 0xF) +byte7 = tau_u & 0xFF +``` + +### State reply (8 bytes, on recv_id) + +Same `q | dq | tau` layout + 2 temperature bytes: + +``` +byte0 = motor_id_echo +byte1..5 = q | dq | tau (same packing as above) +byte6 = t_mos (°C) +byte7 = t_rotor (°C) +``` + +### CTRL_MODE register write + +Broadcast frame on CAN ID `0x7FF`: + +``` +data = [send_id_lo, send_id_hi, 0x55, RID=10, val[0..3]] + where val = 1 (MIT) | 2 (POS_VEL) | 3 (VEL) | 4 (POS_FORCE), little-endian uint32 +``` + +Persistent across power cycles. + +--- + +## Known gotchas + +- **`ip link ... fd on` → `Operation not supported`.** gs_usb firmware doesn't support CAN-FD. Use classical CAN @ 1 Mbit (our bringup script's default). +- **Motors reply to probes but commands do nothing.** CTRL_MODE is not MIT. The adapter now writes MIT on connect, but if you disabled that and motors got reset, run `openarm_set_mit_mode.py`. +- **`COLLISION_AT_START` during planning.** `link5` and `link7` collision meshes overlap by 3 mm at every configuration. Handled by `OPENARM_COLLISION_EXCLUSIONS` in the catalog. If you see it anyway, the exclusion pairs may not be getting applied — check that the collision filter log line appears during world build. +- **`INVALID_START` during planning.** Hardware encoder noise pushed a joint 1 mrad past a URDF limit. Joint4 used to be exactly `lower=0.0` which tripped this — it's now `-0.01` to give breathing room. If you see it on a different joint, widen that limit by ~10 mrad. +- **"Transmit buffer full" (ENOBUFS) at 100 Hz.** Kernel TX queue too small. The bringup script sets `txqueuelen 1000`; the driver also retries on ENOBUFS. If you still see the error, check `ip -details link show canX | grep qlen`. +- **Arms swap sides.** USB enumeration order flipped. Swap `LEFT_CAN` / `RIGHT_CAN` in [blueprints.py](/dimos/robot/manipulators/openarm/blueprints.py). + +--- + +## Design decisions + +- **Driver separate from adapter.** `driver.py` has zero dimos deps → unit-testable with a virtual CAN bus, reusable outside dimos. +- **MIT mode for everything.** MIT can emulate position (high kp), velocity (kp=0, nonzero kd+dq), and torque (kp=kd=0, nonzero tau). One code path. +- **Gravity compensation on by default.** Eliminates steady-state position error without needing high kp. Needs Pinocchio + the per-side URDFs. +- **One adapter per CAN bus, keyed by `address`.** Matches the Piper adapter pattern. Bimanual = two adapters with different `address` values. +- **Per-side URDFs for Drake planning.** Loading the full 14-DOF bimanual URDF twice (once per robot instance) creates phantom-arm collisions with the "other" arm frozen at zero. The per-side URDFs keep only one arm's links + the torso, avoiding the phantom collisions while matching the bimanual kinematics exactly. +- **URDF stays in-tree (`data/openarm_description/`) for now.** Can migrate to LFS later — only the path constant in the catalog changes. +- **CAN bringup stays manual (`sudo`).** Auto-bringup from `connect()` would need sudo-in-a-library or a systemd unit; the explicit script is clearer and testable. For production, add a oneshot systemd unit that runs the script at boot. + +--- + +## Workspace analysis + +For figuring out which targets are reachable before planning, use the generic workspace tool: + +```bash +# Visualize the left arm's reachable workspace as a point cloud +python -m dimos.utils.workspace data/openarm_description/urdf/robot/openarm_v10_left.urdf + +# Check if a specific target is reachable +python -m dimos.utils.workspace data/openarm_description/urdf/robot/openarm_v10_left.urdf query 0.1 0.3 0.5 + +# Get a list of reachable poses near a target, ranked by manipulability +python -m dimos.utils.workspace data/openarm_description/urdf/robot/openarm_v10_left.urdf suggest 0.1 0.3 0.5 + +# Interactive: visualize + type targets to query +python -m dimos.utils.workspace data/openarm_description/urdf/robot/openarm_v10_left.urdf interactive +``` + +Points are colored by Yoshikawa manipulability index: green = dexterous, red = near singularity. Avoid planning targets in the red regions. + +--- + +## Testing + +```bash +# Unit tests (no hardware, use virtual CAN) +.venv/bin/python -m pytest dimos/hardware/manipulators/openarm/ -v +``` + +Expected: 24 passed (13 driver + 11 adapter). All tests use `can.Bus(interface="virtual")` loopback — no real hardware needed. diff --git a/docs/requirements.md b/docs/requirements.md index 856f0bc9ac..f27d2a0a47 100644 --- a/docs/requirements.md +++ b/docs/requirements.md @@ -28,21 +28,24 @@ Bare `pip install dimos` installs the **core** tier. Extras add capabilities on top. ```bash -pip install dimos # Core only -pip install 'dimos[base,unitree]' # Full stack + Unitree -pip install 'dimos[base,unitree,sim]' # + MuJoCo simulation -pip install 'dimos[base,unitree,drone]' # + Drone support -pip install 'dimos[base,unitree,manipulation]' # + Arm control +pip install dimos # Core only +pip install 'dimos[base,unitree]' # Unitree robot control (no torch) +pip install 'dimos[base,unitree,perception]' # + Object detection, VLMs (requires torch) +pip install 'dimos[base,unitree,sim]' # + MuJoCo simulation +pip install 'dimos[base,unitree,perception,sim]' # Full stack +pip install 'dimos[base,unitree,drone]' # + Drone support +pip install 'dimos[base,unitree,manipulation]' # + Arm control ``` | Extra | What it adds | Key packages | GPU? | |-------|-------------|--------------|------| | *(core)* | Transport, streams, CLI, blueprints, occupancy maps | dimos-lcm, numpy, scipy, opencv, open3d, numba, Pinocchio, typer, textual | No | -| `agents` | LLM agent, speech, tool use | langchain, openai, whisper, anthropic | No | +| `agents` | LLM agent, speech, tool use | langchain, openai, faster-whisper, anthropic | No | | `perception` | Object detection, VLMs, tracking | ultralytics, transformers, moondream | **Yes** | | `visualization` | Rerun viewer + bridge | rerun-sdk, dimos-viewer | No | | `web` | FastAPI web interface, audio | fastapi, uvicorn, ffmpeg-python | No | | `sim` | MuJoCo simulation | mujoco, playground, pygame | No | +| `whisper` | OpenAI Whisper STT (full, requires torch) | openai-whisper | **Yes** | | `unitree` | Unitree Go2 / G1 support | unitree-webrtc-connect | No | | `drone` | DJI Tello / MAVLink drones | pymavlink | No | | `manipulation` | Arm planning + control | Drake, piper-sdk, xarm-sdk | No | @@ -50,7 +53,7 @@ pip install 'dimos[base,unitree,manipulation]' # + Arm control | `cpu` | CPU inference backends | onnxruntime, ctransformers | No | | `misc` | Extra models, embeddings, hardware SDKs | cerebras, edgetam, sentence-transformers, tiktoken | Varies | | `docker` | Minimal set for Docker sidecar modules | dimos-lcm, numpy, opencv-headless, rerun-sdk | No | -| `base` | Kitchen sink (agents + web + perception + viz + sim) | All of the above | **Yes** | +| `base` | Standard stack (agents + web + viz) | langchain, fastapi, rerun-sdk | No | | `dev` | Linting, testing, type stubs | ruff, mypy, pytest, pre-commit | No | | `psql` | PostgreSQL storage | psycopg2 | No | | `dds` | DDS transport (CycloneDDS) | dev + cyclonedds | No | From a7aa3bf468f635a1f22807f67ac6af8134818ee6 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 13:39:40 -0700 Subject: [PATCH 15/23] fix(coordinator): merge duplicate _create_whole_body_adapter MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Both Mustafa's #1954 (already on dev) and the GR00T-WBC PR added this method. After the merge, both definitions live in coordinator.py — Python uses the second, the first becomes dead code, and the transport adapter (which depends on hardware_id being passed) silently picks up its default ``"wholebody"`` topic prefix instead of the component's id. Collapse to one definition that passes the union of kwargs both adapters need: dof, hardware_id, network_interface, domain_id, address, plus **adapter_kwargs. Adapters tolerate extras via their constructor's **_ catch-all. --- dimos/control/coordinator.py | 36 ++++++++++-------------------------- 1 file changed, 10 insertions(+), 26 deletions(-) diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index fe526d128f..64eed4c213 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -322,35 +322,15 @@ def _create_twist_base_adapter(self, component: HardwareComponent) -> TwistBaseA def _create_whole_body_adapter(self, component: HardwareComponent) -> WholeBodyAdapter: """Create a whole-body adapter from component config. - ``component.address`` carries the DDS network interface — int (CAN port) - or str ("enp60s0"); cyclonedds requires the right type, so try int() first - and fall back to keeping the original string. + ``component.address`` is overloaded: real-hw adapters use it as + the DDS network interface (str ``"enp60s0"`` or int CAN port); + sim adapters use it as the MJCF path (str). We pass it under + both ``network_interface`` and ``address`` so each registered + adapter can pick whichever is meaningful — extras flow through + ``**component.adapter_kwargs``. """ from dimos.hardware.whole_body.registry import whole_body_adapter_registry - addr: int | str | None = component.address - if addr is not None: - try: - addr = int(addr) - except ValueError: - pass # keep as string (e.g. "enp60s0") - - return whole_body_adapter_registry.create( - component.adapter_type, - dof=len(component.joints), - hardware_id=component.hardware_id, - network_interface=addr if addr is not None else "", - **component.adapter_kwargs, - ) - - def _create_whole_body_adapter(self, component: HardwareComponent) -> object: - """Create a whole-body adapter from component config.""" - from dimos.hardware.whole_body.registry import whole_body_adapter_registry - - # ``address`` is overloaded: real-hw adapters use it as the DDS - # network interface (string like "enp60s0" or int). Sim adapters - # use it as the MJCF path (string). Pass it raw under both names - # so each adapter can pick whichever is meaningful. addr = component.address net_iface: int | str = 0 if addr is not None: @@ -358,11 +338,15 @@ def _create_whole_body_adapter(self, component: HardwareComponent) -> object: net_iface = int(addr) except ValueError: net_iface = addr + return whole_body_adapter_registry.create( component.adapter_type, + dof=len(component.joints), + hardware_id=component.hardware_id, network_interface=net_iface, domain_id=component.domain_id, address=addr, + **component.adapter_kwargs, ) def _create_task_from_config(self, cfg: TaskConfig) -> ControlTask: From 74b6404491e2ae723baefccece74b23462c3584e Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 14:10:37 -0700 Subject: [PATCH 16/23] refactor(g1-wbc): drop monolith adapter, use Mustafa's transport bridge MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Switch unitree-g1-groot-wbc to the architecture Mustafa landed in #1954 (G1WholeBodyConnection Module + TransportWholeBodyAdapter via LCM bridge), matching unitree-g1-coordinator. Single G1 low-level pattern in the codebase now. * Delete dimos/hardware/whole_body/unitree/g1/adapter.py — the UnitreeG1LowLevelAdapter (single-process DDS) is gone. * Rewrite unitree_g1_groot_wbc.py to compose G1WholeBodyConnection + ControlCoordinator(adapter_type="transport_lcm") + dashboard via autoconnect. * Patch wholebody_connection.py to apply the macOS-cyclonedds fixes the dropped monolith was carrying: - Init(None, 0) instead of Init(callback, 10) - Hardcode mode_machine = 5 (the static value for 29-DOF G1) - publish_loop polls subscriber.Read() per tick - Drop the now-unused _on_low_state callback --- .../hardware/whole_body/unitree/g1/adapter.py | 312 ------------------ .../blueprints/basic/unitree_g1_groot_wbc.py | 101 +++--- .../robot/unitree/g1/wholebody_connection.py | 42 +-- 3 files changed, 75 insertions(+), 380 deletions(-) delete mode 100644 dimos/hardware/whole_body/unitree/g1/adapter.py diff --git a/dimos/hardware/whole_body/unitree/g1/adapter.py b/dimos/hardware/whole_body/unitree/g1/adapter.py deleted file mode 100644 index 934265300d..0000000000 --- a/dimos/hardware/whole_body/unitree/g1/adapter.py +++ /dev/null @@ -1,312 +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. - -"""Unitree G1 low-level adapter -- direct 29-DOF joint control over DDS. - -Uses ``rt/lowcmd`` / ``rt/lowstate`` DDS topics for motor-level -position/velocity/torque control, bypassing the high-level LocoClient. - -Important: The G1 must first exit sport mode (via MotionSwitcherClient) -before low-level commands are accepted. - -Motor ordering (29 joints): - 0-5: Left leg (HipPitch, HipRoll, HipYaw, Knee, AnklePitch, AnkleRoll) - 6-11: Right leg - 12: WaistYaw - 13-14: WaistRoll, WaistPitch (may be invalid on some variants) - 15-21: Left arm (ShoulderPitch, ShoulderRoll, ShoulderYaw, Elbow, - WristRoll, WristPitch, WristYaw) - 22-28: Right arm - -G1-specific protocol details: - - Uses ``unitree_hg`` IDL types (not ``unitree_go`` like the Go2) - - LowCmd has ``mode_pr`` and ``mode_machine`` fields instead of head/level_flag - - ``mode_machine`` must be read from LowState and echoed back in every LowCmd - - Motor array has 35 slots (only 29 are used) -""" - -from __future__ import annotations - -import threading -import time -from typing import TYPE_CHECKING - -from dimos.hardware.whole_body.spec import ( - POS_STOP, - VEL_STOP, - IMUState, - MotorCommand, - MotorState, -) -from dimos.utils.logging_config import setup_logger - -if TYPE_CHECKING: - from dimos.hardware.whole_body.registry import WholeBodyAdapterRegistry - from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped - -logger = setup_logger() - -_NUM_MOTORS = 29 -_NUM_MOTOR_SLOTS = 35 - - -class UnitreeG1LowLevelAdapter: - """WholeBodyAdapter implementation for Unitree G1 -- low-level DDS. - - The coordinator's tick loop drives the publish cadence. Each call to - ``write_motor_commands()`` updates the ``LowCmd_`` buffer, computes - CRC, and publishes immediately -- no background thread needed. - - Args: - network_interface: DDS network interface name or ID (default: "eth0"). - domain_id: DDS domain ID. Real robot uses 0; unitree_mujoco sim - defaults to 1. Changing domain lets the same adapter bind to - sim or real with no code change. - """ - - def __init__( - self, - network_interface: int | str = 0, - domain_id: int = 0, - **_: object, - ) -> None: - self._network_interface = network_interface - self._domain_id = domain_id - - self._connected = False - self._lock = threading.Lock() - - # SDK objects (lazy-imported on connect) - self._low_cmd = None - self._publisher = None - self._subscriber = None - self._crc = None - - # Latest feedback - self._low_state = None - - # mode_machine must be read from first LowState and echoed back - self._mode_machine: int | None = None - - # ========================================================================= - # Connection - # ========================================================================= - - def connect(self) -> bool: - """Connect to G1 and release sport mode for low-level control.""" - try: - from unitree_sdk2py.core.channel import ( - ChannelFactoryInitialize, - ChannelPublisher, - ChannelSubscriber, - ) - from unitree_sdk2py.idl.default import unitree_hg_msg_dds__LowCmd_ - from unitree_sdk2py.idl.unitree_hg.msg.dds_ import LowCmd_, LowState_ - from unitree_sdk2py.utils.crc import CRC - - # 1. Initialise DDS transport. NOTE: the cyclonedds Python - # wheel reads CYCLONEDDS_HOME at runtime — it must point at - # the local cyclonedds install (e.g. ~/cyclonedds/install) - # before this call or DDS topic creation later fails with - # PRECONDITION_NOT_MET. Add to your shell rc. - logger.info( - f"Initializing DDS (G1 low-level) with interface {self._network_interface} " - f"on domain {self._domain_id}..." - ) - ChannelFactoryInitialize(self._domain_id, self._network_interface) - - # 2. Create publisher / subscriber - self._publisher = ChannelPublisher("rt/lowcmd", LowCmd_) - self._publisher.Init() - - # Passive subscriber — Read() per tick, no callback. Avoids - # the macOS cyclonedds callback-not-firing footgun that bit - # us when this was Init(self._on_low_state, 10). - self._subscriber = ChannelSubscriber("rt/lowstate", LowState_) - self._subscriber.Init(None, 0) - - # 3. Initialise LowCmd with safe defaults. ``mode_machine`` - # is hardcoded to 5 (the unitree-legged-const value for the - # 29-DOF G1). Earlier the adapter blocked here waiting for a - # first LowState to read it back; the macOS cyclonedds - # callback never fires reliably for that, and the value is - # static for this hardware variant — so we just set it. - self._low_cmd = unitree_hg_msg_dds__LowCmd_() - self._low_cmd.mode_pr = 0 # PR mode (Pitch/Roll) - self._mode_machine = 5 - self._low_cmd.mode_machine = self._mode_machine - for i in range(_NUM_MOTOR_SLOTS): - self._low_cmd.motor_cmd[i].mode = 0x01 # Enable - self._low_cmd.motor_cmd[i].q = POS_STOP - self._low_cmd.motor_cmd[i].kp = 0 - self._low_cmd.motor_cmd[i].dq = VEL_STOP - self._low_cmd.motor_cmd[i].kd = 0 - self._low_cmd.motor_cmd[i].tau = 0 - - self._crc = CRC() - - # 4. Release sport mode so low-level commands are accepted - logger.info("Releasing sport mode...") - self._release_sport_mode() - - self._connected = True - logger.info(f"G1 low-level adapter connected (mode_machine={self._mode_machine})") - return True - - except Exception: - logger.exception("Failed to connect G1 low-level adapter (full traceback):") - self._connected = False - return False - - def disconnect(self) -> None: - """Disconnect from the robot.""" - self._connected = False - self._publisher = None - self._subscriber = None - self._low_cmd = None - self._low_state = None - self._mode_machine = None - logger.info("G1 low-level adapter disconnected") - - def is_connected(self) -> bool: - return self._connected - - # ========================================================================= - # State Reading - # ========================================================================= - - def has_motor_states(self) -> bool: - """True once we've received at least one LowState frame.""" - self._poll_low_state() - return self._low_state is not None - - def _poll_low_state(self) -> None: - """Drain any pending LowState samples into ``self._low_state``. - - Passive-subscriber pattern: ``Read()`` per tick. None means no - fresh sample (treat as drop / keep last value). - """ - if self._subscriber is None: - return - sample = self._subscriber.Read() - if sample is not None: - self._low_state = sample - - def read_motor_states(self) -> list[MotorState]: - """Read motor states for all 29 joints.""" - self._poll_low_state() - with self._lock: - if self._low_state is None: - return [MotorState()] * _NUM_MOTORS - return [ - MotorState( - q=self._low_state.motor_state[i].q, - dq=self._low_state.motor_state[i].dq, - tau=self._low_state.motor_state[i].tau_est, - ) - for i in range(_NUM_MOTORS) - ] - - def read_imu(self) -> IMUState: - """Read IMU state.""" - self._poll_low_state() - with self._lock: - if self._low_state is None: - return IMUState() - imu = self._low_state.imu_state - return IMUState( - quaternion=tuple(imu.quaternion), - gyroscope=tuple(imu.gyroscope), - accelerometer=tuple(imu.accelerometer), - rpy=tuple(imu.rpy), - ) - - def read_odom(self) -> PoseStamped | None: - """Real G1 odom — not yet wired. - - The unitree_sdk2py LowState only carries IMU + motor data, not a - base-frame pose; the production pipeline computes odometry by - fusing IMU integration with leg kinematics in a separate node. - Returning None keeps the coordinator's Out[odom] silent on real - hardware. Wire this up by either (a) subscribing to the DDS - odometry topic published by the onboard estimator if available, - or (b) running a small estimator inside this adapter. - """ - return None - - # ========================================================================= - # Control - # ========================================================================= - - def write_motor_commands(self, commands: list[MotorCommand]) -> bool: - """Update command buffer, compute CRC, and publish immediately. - - Called by the coordinator tick loop on every tick -- no background - thread needed. - """ - if len(commands) != _NUM_MOTORS: - logger.error(f"Expected {_NUM_MOTORS} commands, got {len(commands)}") - return False - - with self._lock: - if self._low_cmd is None or self._crc is None or self._publisher is None: - return False - if self._mode_machine is None: - return False - - # Echo mode_machine from latest LowState - self._low_cmd.mode_machine = self._mode_machine - - for i, cmd in enumerate(commands): - self._low_cmd.motor_cmd[i].q = cmd.q - self._low_cmd.motor_cmd[i].dq = cmd.dq - self._low_cmd.motor_cmd[i].kp = cmd.kp - self._low_cmd.motor_cmd[i].kd = cmd.kd - self._low_cmd.motor_cmd[i].tau = cmd.tau - self._low_cmd.crc = self._crc.Crc(self._low_cmd) - self._publisher.Write(self._low_cmd) - return True - - # ========================================================================= - # Internal - # ========================================================================= - - def _release_sport_mode(self) -> None: - """Exit sport mode so that low-level commands are accepted. - - Loops ReleaseMode until CheckMode returns empty. - """ - from unitree_sdk2py.comm.motion_switcher.motion_switcher_client import ( - MotionSwitcherClient, - ) - - msc = MotionSwitcherClient() - msc.SetTimeout(5.0) - msc.Init() - - _status, result = msc.CheckMode() - while result and result.get("name"): - msc.ReleaseMode() - _status, result = msc.CheckMode() - time.sleep(1) - - logger.info("Sport mode released -- low-level control active") - - -def register(registry: WholeBodyAdapterRegistry) -> None: - """Register this adapter with the whole-body registry.""" - registry.register("unitree_g1", UnitreeG1LowLevelAdapter) - - -__all__ = ["UnitreeG1LowLevelAdapter"] diff --git a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc.py b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc.py index 72d55c47bf..21bd86ec3f 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc.py +++ b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc.py @@ -14,43 +14,39 @@ """Unitree G1 GR00T whole-body-control blueprint — real hardware. -Runs the ControlCoordinator at 500 Hz with two tasks: - - - ``groot_wbc`` (priority 50) claims legs + waist (15 DOF) and runs - the GR00T balance / walk ONNX policies at 50 Hz. - - ``servo_arms`` (priority 10) claims the 14 arm joints and holds - them at the relaxed pose the policy was trained against. - -Real-hardware safety profile: the blueprint comes up unarmed and in -dry-run. The operator opens the dashboard at http://localhost:7779/, -verifies the computed commands look sane, then clicks Activate to -ramp from the current pose to the bent-knee default over 10 s before -handing torque control to the policy. - -Architecture: - dashboard WASD ──▶ WebsocketVisModule ──▶ LCM /g1/cmd_vel - │ - coordinator twist_command ──▶ GrootWBCTask - │ - ControlCoordinator ──joint_state──▶ LCM /coordinator/joint_state - ◀─joint_command── LCM /g1/joint_command - -Sim is a separate blueprint (``unitree-g1-groot-wbc-sim``) so each -file is statically clear about what it composes — no module-level -config branching. +Composes three Modules: + + G1WholeBodyConnection ─ owns DDS rt/lowstate / rt/lowcmd in its own + worker; publishes motor_states + imu over + LCM, subscribes motor_command from LCM. + ControlCoordinator ─ runs at 500 Hz with two tasks: + * groot_wbc (priority 50) legs+waist (15 DOF), GR00T balance/ + walk ONNX policies at 50 Hz. + * servo_arms (priority 10) 14 arm joints, hold relaxed pose. + WebsocketVisModule ─ operator dashboard at :7779 (Arm + Dry-Run + toggles, WASD teleop). + +The coordinator's ``transport_lcm`` whole-body adapter bridges to the +connection module via LCM, mirroring Mustafa's ``unitree-g1-coordinator`` +blueprint — single architectural pattern for G1 low-level work. + +Real-hardware safety profile: comes up unarmed and in dry-run. Operator +verifies computed commands in the dashboard, then clicks Activate to +ramp from current pose to the bent-knee default over 10 s before handing +torque control to the policy. + +Sim is a separate blueprint (``unitree-g1-groot-wbc-sim``). Usage: ROBOT_INTERFACE=enp86s0 dimos run unitree-g1-groot-wbc Environment: - ROBOT_INTERFACE DDS network interface for the real robot - (default ``"enp86s0"``). - DIMOS_DDS_DOMAIN DDS domain id (default ``0``). - CYCLONEDDS_HOME Required at runtime — must point at the - cyclonedds C install (e.g. ``~/cyclonedds/install``). + ROBOT_INTERFACE DDS network interface (default ``"enp86s0"``). + CYCLONEDDS_HOME Required at runtime — must point at the cyclonedds + C install (e.g. ``~/cyclonedds/install``). Add the + export to your shell rc. GROOT_MODEL_DIR Directory containing ``balance.onnx`` + - ``walk.onnx`` (default: pulled via - ``get_data("groot")``). + ``walk.onnx`` (default: pulled via ``get_data("groot")``). """ from __future__ import annotations @@ -64,7 +60,9 @@ from dimos.hardware.whole_body.spec import WholeBodyConfig from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped from dimos.msgs.geometry_msgs.Twist import Twist +from dimos.msgs.sensor_msgs.Imu import Imu from dimos.msgs.sensor_msgs.JointState import JointState +from dimos.msgs.sensor_msgs.MotorCommandArray import MotorCommandArray from dimos.msgs.std_msgs.Bool import Bool as DimosBool from dimos.robot.unitree.g1.blueprints.basic._groot_wbc_common import ( ARM_DEFAULT_POSE, @@ -74,9 +72,15 @@ g1_joints, g1_legs_waist, ) +from dimos.robot.unitree.g1.wholebody_connection import G1WholeBodyConnection from dimos.utils.data import get_data from dimos.web.websocket_vis.websocket_vis_module import WebsocketVisModule +_g1_connection = G1WholeBodyConnection.blueprint( + release_sport_mode=True, + network_interface=os.getenv("ROBOT_INTERFACE", "enp86s0"), +) + _g1_coordinator = ControlCoordinator.blueprint( tick_rate=500.0, publish_joint_state=True, @@ -86,10 +90,7 @@ hardware_id="g1", hardware_type=HardwareType.WHOLE_BODY, joints=g1_joints, - adapter_type="unitree_g1", - address=os.getenv("ROBOT_INTERFACE", "enp86s0"), - domain_id=int(os.getenv("DIMOS_DDS_DOMAIN", "0")), - auto_enable=True, + adapter_type="transport_lcm", wb_config=WholeBodyConfig(kp=tuple(G1_GROOT_KP), kd=tuple(G1_GROOT_KD)), ), ], @@ -118,28 +119,30 @@ auto_start=True, ), ], -).transports( +) + +# Operator dashboard at http://localhost:7779/ — Arm + Dry-Run toggles, +# WASD teleop captured in the browser DOM (sidesteps the macOS Cocoa +# main-thread restriction that breaks pygame-based teleop). +_g1_ws_vis = WebsocketVisModule.blueprint() + +unitree_g1_groot_wbc = autoconnect(_g1_connection, _g1_coordinator, _g1_ws_vis).transports( { + # Bridge: G1WholeBodyConnection ↔ ControlCoordinator (transport_lcm). + # Topic prefix is the HardwareComponent's hardware_id ("g1"). + ("motor_states", JointState): LCMTransport("/g1/motor_states", JointState), + ("imu", Imu): LCMTransport("/g1/imu", Imu), + ("motor_command", MotorCommandArray): LCMTransport("/g1/motor_command", MotorCommandArray), + # Coordinator outputs. ("joint_state", JointState): LCMTransport("/coordinator/joint_state", JointState), ("odom", PoseStamped): LCMTransport("/odom", PoseStamped), ("joint_command", JointState): LCMTransport("/g1/joint_command", JointState), + # Dashboard ↔ coordinator (cmd_vel + activate + dry_run). ("twist_command", Twist): LCMTransport("/g1/cmd_vel", Twist), ("activate", DimosBool): LCMTransport("/g1/activate", DimosBool), ("dry_run", DimosBool): LCMTransport("/g1/dry_run", DimosBool), - } -) - -# Operator dashboard (WASD, Activate, dry-run toggle) at -# http://localhost:7779/. WebsocketVisModule re-publishes the -# dashboard's events onto the coordinator's LCM ports. -_g1_ws_vis = WebsocketVisModule.blueprint().transports( - { ("cmd_vel", Twist): LCMTransport("/g1/cmd_vel", Twist), - ("activate", DimosBool): LCMTransport("/g1/activate", DimosBool), - ("dry_run", DimosBool): LCMTransport("/g1/dry_run", DimosBool), - }, + } ) -unitree_g1_groot_wbc = autoconnect(_g1_coordinator, _g1_ws_vis) - __all__ = ["unitree_g1_groot_wbc"] diff --git a/dimos/robot/unitree/g1/wholebody_connection.py b/dimos/robot/unitree/g1/wholebody_connection.py index f4fb762bae..4eef2b9efd 100644 --- a/dimos/robot/unitree/g1/wholebody_connection.py +++ b/dimos/robot/unitree/g1/wholebody_connection.py @@ -51,7 +51,12 @@ _NUM_MOTORS = 29 _NUM_MOTOR_SLOTS = 35 # G1 hg LowCmd has 35 slots; only 29 are used -_MODE_MACHINE_WAIT_S = 10.0 +# mode_machine is a static value identifying the G1 firmware/hardware +# variant. Older code read it back from the first LowState frame and +# echoed it into LowCmd; that callback path is unreliable on macOS +# cyclonedds, and the value never changes for a given robot, so we +# hardcode it. 29-DOF G1 (gear) reports 5. +_MODE_MACHINE_G1: int = 5 # Joint names sourced from the canonical helper. Order matches the motor index # convention above. Single-source-of-truth so any coordinator-side adapter built @@ -119,12 +124,19 @@ def start(self) -> None: self._publisher = ChannelPublisher("rt/lowcmd", LowCmd_) self._publisher.Init() + # Passive subscriber — Read() per tick from the publish loop. The + # callback variant (Init(self._on_low_state, 10)) doesn't fire + # reliably under cyclonedds on macOS, which used to leave us + # blocked here forever waiting for a first LowState. self._subscriber = ChannelSubscriber("rt/lowstate", LowState_) - self._subscriber.Init(self._on_low_state, 10) + self._subscriber.Init(None, 0) # POS_STOP/VEL_STOP + zero gains so the robot can't twitch pre-command. self._low_cmd = unitree_hg_msg_dds__LowCmd_() self._low_cmd.mode_pr = 0 # PR (pitch/roll) mode + # mode_machine is a static value (see comment above the constant). + self._mode_machine = _MODE_MACHINE_G1 + self._low_cmd.mode_machine = self._mode_machine for i in range(_NUM_MOTOR_SLOTS): self._low_cmd.motor_cmd[i].mode = 0x01 # enable self._low_cmd.motor_cmd[i].q = POS_STOP @@ -141,16 +153,6 @@ def start(self) -> None: else: logger.info("Skipping sport mode release (release_sport_mode=False)") - logger.info("Waiting for first LowState to capture mode_machine...") - deadline = time.time() + _MODE_MACHINE_WAIT_S - while self._mode_machine is None and time.time() < deadline: - time.sleep(0.1) - if self._mode_machine is None: - raise RuntimeError( - f"Timed out after {_MODE_MACHINE_WAIT_S:.1f}s waiting for " - f"first LowState — mode_machine never captured" - ) - logger.info(f"G1WholeBodyConnection connected (mode_machine={self._mode_machine})") self.register_disposable(Disposable(self.motor_command.subscribe(self._on_motor_command))) @@ -201,6 +203,15 @@ def _publish_loop(self) -> None: zero_vec3 = (0.0, 0.0, 0.0) while not self._stop_event.is_set(): + # Drain the latest LowState frame (None means no fresh sample + # this tick — keep the previous one). + sub = self._subscriber + if sub is not None: + fresh = sub.Read() + if fresh is not None: + with self._lock: + self._low_state = fresh + with self._lock: ls = self._low_state if ls is None: @@ -276,13 +287,6 @@ def _on_motor_command(self, msg: MotorCommandArray) -> None: self._low_cmd.crc = self._crc.Crc(self._low_cmd) self._publisher.Write(self._low_cmd) - def _on_low_state(self, msg: Any) -> None: - """rt/lowstate callback — captures mode_machine and the latest snapshot.""" - with self._lock: - self._low_state = msg - if self._mode_machine is None: - self._mode_machine = msg.mode_machine - def _release_sport_mode(self) -> None: """Loop ReleaseMode until MotionSwitcher reports no active controller.""" from unitree_sdk2py.comm.motion_switcher.motion_switcher_client import ( From 7f91e52be380630bfa45eab89c97f5e3a82ca9c3 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 14:23:24 -0700 Subject: [PATCH 17/23] fix(g1-wbc-sim): resolve MJCF path via get_data so CWD doesn't matter _MJCF_PATH was a relative path "data/mujoco_sim/g1_gear_wbc.xml" which only resolved when dimos was launched from the repo root. The mujoco viewer subprocess inherits CWD from the launching shell, so running ``dimos run unitree-g1-groot-wbc-sim`` from any other directory tripped FileNotFoundError on viewer startup. get_data("mujoco_sim") resolves the absolute install path and auto-extracts the LFS tarball on first run. --- .../unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py index af2a319542..9836597697 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py +++ b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py @@ -53,7 +53,9 @@ logger = setup_logger() -_MJCF_PATH = "data/mujoco_sim/g1_gear_wbc.xml" +# Resolve via get_data so the path works regardless of CWD and the +# tarball is auto-extracted from LFS on first run. +_MJCF_PATH = str(get_data("mujoco_sim") / "g1_gear_wbc.xml") _g1_engine = MujocoSimModule.blueprint( address=_MJCF_PATH, From 117df923f96ffd9a80446e8d9c545c666b7b6c66 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 15:32:16 -0700 Subject: [PATCH 18/23] refactor(g1-wbc): paul-review fixes + bridge composition smoke test MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit 1. unitree_g1_groot_wbc_sim.py: resolve _MJCF_PATH via get_data so both MujocoSimModule and the DIMOS_MUJOCO_VIEW=1 subprocess open the file regardless of shell CWD. Earlier the relative path "data/mujoco_sim/g1_gear_wbc.xml" only worked from the repo root. 2. wholebody_connection.py: hardcoded mode_machine = 5 has no fallback if a future G1 firmware revision changes the value. Add a one-shot warning the first time we read a LowState whose mode_machine doesn't match. Self-disables after the first log line so it doesn't spam the operator. 3. test_unitree_g1_groot_wbc.py: composition smoke test verifying the three deployed modules, bridge adapter binding (transport_lcm, confirming the migration off the deleted unitree_g1 monolith), real-hw safety profile (auto_arm=False, auto_dry_run=True, default_ramp_seconds=10.0), servo_arms defaults, and all bridge + dashboard LCM topics. No DDS, no hardware — just module imports. --- .../basic/test_unitree_g1_groot_wbc.py | 115 ++++++++++++++++++ .../basic/unitree_g1_groot_wbc_sim.py | 6 +- .../robot/unitree/g1/wholebody_connection.py | 19 ++- 3 files changed, 137 insertions(+), 3 deletions(-) create mode 100644 dimos/robot/unitree/g1/blueprints/basic/test_unitree_g1_groot_wbc.py diff --git a/dimos/robot/unitree/g1/blueprints/basic/test_unitree_g1_groot_wbc.py b/dimos/robot/unitree/g1/blueprints/basic/test_unitree_g1_groot_wbc.py new file mode 100644 index 0000000000..ad3862c4f6 --- /dev/null +++ b/dimos/robot/unitree/g1/blueprints/basic/test_unitree_g1_groot_wbc.py @@ -0,0 +1,115 @@ +# 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. + +"""Composition smoke tests for ``unitree_g1_groot_wbc`` (real-hw blueprint). + +These tests do not exercise DDS or actually run anything — they just +verify that the blueprint composes correctly: + + * imports cleanly without the ``[unitree-dds]`` extra installed + * deploys the three expected modules (connection + coordinator + dashboard) + * picks the bridge adapter (``transport_lcm``) on the G1 hardware + component, so the GR00T-WBC PR really did migrate off the deleted + ``unitree_g1`` monolith + * wires the LCM topics the coordinator's safety state machine needs + (``/g1/activate``, ``/g1/dry_run``, ``/g1/cmd_vel``) and the + bridge's own ports (``/g1/motor_states``, ``/g1/imu``, ``/g1/motor_command``) + * keeps the real-hw safety profile on the GR00T task (unarmed + + dry-run + 10-s ramp). +""" + +from __future__ import annotations + +from dimos.robot.unitree.g1.blueprints.basic.unitree_g1_groot_wbc import ( + unitree_g1_groot_wbc, +) + + +def _module_names() -> set[str]: + return {atom.module.__name__ for atom in unitree_g1_groot_wbc.blueprints} + + +def _coordinator_kwargs() -> dict: + for atom in unitree_g1_groot_wbc.blueprints: + if atom.module.__name__ == "ControlCoordinator": + return atom.kwargs + raise AssertionError("ControlCoordinator not in blueprint composition") + + +def test_blueprint_composes_three_expected_modules() -> None: + assert _module_names() == { + "G1WholeBodyConnection", + "ControlCoordinator", + "WebsocketVisModule", + } + + +def test_g1_hardware_uses_bridge_adapter() -> None: + """We deleted the monolith ``unitree_g1`` adapter — verify the + coordinator now binds via Mustafa's bridge (``transport_lcm``).""" + hw = _coordinator_kwargs()["hardware"] + assert len(hw) == 1, "expected exactly one hardware component" + g1 = hw[0] + assert g1.hardware_id == "g1" + assert g1.adapter_type == "transport_lcm" + assert len(g1.joints) == 29 + assert g1.wb_config is not None + assert g1.wb_config.kp is not None and len(g1.wb_config.kp) == 29 + assert g1.wb_config.kd is not None and len(g1.wb_config.kd) == 29 + + +def test_groot_task_is_safety_gated() -> None: + """Real-hw blueprint must come up unarmed + dry-run + with a 10-s ramp. + + Sim auto-arms with no ramp via the sister ``unitree_g1_groot_wbc_sim`` + blueprint; that path is not under test here. + """ + tasks = _coordinator_kwargs()["tasks"] + groot = next(t for t in tasks if t.name == "groot_wbc") + assert groot.type == "groot_wbc" + assert groot.hardware_id == "g1" + assert groot.priority == 50 + assert groot.auto_arm is False + assert groot.auto_dry_run is True + assert groot.default_ramp_seconds == 10.0 + + +def test_servo_arms_holds_default_pose() -> None: + tasks = _coordinator_kwargs()["tasks"] + servo = next(t for t in tasks if t.name == "servo_arms") + assert servo.type == "servo" + assert servo.priority == 10 + assert servo.default_positions is not None + assert len(servo.default_positions) == 14 # 7 left + 7 right arm joints + + +def test_bridge_topics_wired() -> None: + """Bridge needs motor_states/imu/motor_command on /g1/* and the + coordinator's safety inputs on /g1/activate, /g1/dry_run, /g1/cmd_vel.""" + topic_strings = { + str(t.topic).split("#")[0] for t in unitree_g1_groot_wbc.transport_map.values() + } + expected = { + "/g1/motor_states", + "/g1/imu", + "/g1/motor_command", + "/g1/activate", + "/g1/dry_run", + "/g1/cmd_vel", + "/g1/joint_command", + "/coordinator/joint_state", + "/odom", + } + missing = expected - topic_strings + assert not missing, f"missing transports: {missing}" diff --git a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py index 9836597697..cc7f5bbd47 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py +++ b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py @@ -53,8 +53,10 @@ logger = setup_logger() -# Resolve via get_data so the path works regardless of CWD and the -# tarball is auto-extracted from LFS on first run. +# Resolved to an absolute path so MujocoSimModule (parent) and the +# DIMOS_MUJOCO_VIEW=1 subprocess can both open the file regardless of +# the shell's CWD. get_data also auto-extracts the LFS tarball on +# first run. _MJCF_PATH = str(get_data("mujoco_sim") / "g1_gear_wbc.xml") _g1_engine = MujocoSimModule.blueprint( diff --git a/dimos/robot/unitree/g1/wholebody_connection.py b/dimos/robot/unitree/g1/wholebody_connection.py index 4eef2b9efd..1c69ded344 100644 --- a/dimos/robot/unitree/g1/wholebody_connection.py +++ b/dimos/robot/unitree/g1/wholebody_connection.py @@ -89,8 +89,12 @@ def __init__(self, **kwargs: Any) -> None: self._low_cmd: LowCmd_ | None = None self._low_state: LowState_ | None = None self._crc: CRC | None = None - # mode_machine: read from first LowState, echoed back in every LowCmd. + # mode_machine: hardcoded at start() to the static value for the + # 29-DOF G1. We log a one-shot warning if the first LowState we + # read disagrees — that's the early signal of firmware drift on a + # variant that needs a different value. self._mode_machine: int | None = None + self._mode_machine_verified: bool = False # Guards _low_cmd / _low_state / _mode_machine across DDS, publish, and LCM threads. self._lock = threading.Lock() self._stop_event = threading.Event() @@ -211,6 +215,19 @@ def _publish_loop(self) -> None: if fresh is not None: with self._lock: self._low_state = fresh + # One-shot sanity check on the hardcoded mode_machine. + if not self._mode_machine_verified: + self._mode_machine_verified = True + actual = int(getattr(fresh, "mode_machine", -1)) + if actual != self._mode_machine: + logger.warning( + f"mode_machine mismatch: hardcoded " + f"{self._mode_machine}, robot reports " + f"{actual}. Commands may be silently " + f"rejected by firmware — set " + f"_MODE_MACHINE_G1 to {actual} for this " + f"variant." + ) with self._lock: ls = self._low_state From 995c735fab33fb7021a2ebae147dc78cdb6f8bc6 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 15:58:54 -0700 Subject: [PATCH 19/23] fix(g1-wbc): safe-stop lowcmd on disconnect + skip release when idle MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Two safety fixes for back-to-back ``dimos run`` cycles on real hardware: 1. ``stop()`` now sends a final ``LowCmd_`` with ``mode=0x00`` (motors disabled) for every motor slot before closing the DDS publisher. Previously the last commanded pose lingered in the motor controllers — when the next process opened a publisher and re-released sport mode, those stale stiff commands fought the new participant during the handoff window, producing audible gearbox stress. 2. ``_release_sport_mode()`` bails immediately if the first ``CheckMode()`` reports nothing active (``result is None`` or ``{"name": ""}``). A clean second start now logs "Sport mode already released — skipping ReleaseMode" and skips the loop-and-poll dance entirely, removing the handoff window. --- .../robot/unitree/g1/wholebody_connection.py | 42 ++++++++++++++++++- 1 file changed, 40 insertions(+), 2 deletions(-) diff --git a/dimos/robot/unitree/g1/wholebody_connection.py b/dimos/robot/unitree/g1/wholebody_connection.py index 1c69ded344..9f08098ac5 100644 --- a/dimos/robot/unitree/g1/wholebody_connection.py +++ b/dimos/robot/unitree/g1/wholebody_connection.py @@ -173,6 +173,29 @@ def stop(self) -> None: self._publish_thread.join(timeout=DEFAULT_THREAD_JOIN_TIMEOUT) self._publish_thread = None + # Final safe-stop lowcmd: disable every motor (mode=0x00, kp=kd=0, + # tau=0). Without this, the motors freeze stiffly at whatever + # the last commanded pose was and the next ``dimos run`` opens + # against a robot that's actively fighting its own controllers + # — observed as horrible mechanical noise during sport-mode + # release. Best-effort: any failure is logged, not raised, so + # cleanup still drains the DDS endpoints. + if self._publisher is not None and self._low_cmd is not None and self._crc is not None: + try: + with self._lock: + for i in range(_NUM_MOTOR_SLOTS): + self._low_cmd.motor_cmd[i].mode = 0x00 # disable + self._low_cmd.motor_cmd[i].q = POS_STOP + self._low_cmd.motor_cmd[i].dq = VEL_STOP + self._low_cmd.motor_cmd[i].kp = 0 + self._low_cmd.motor_cmd[i].kd = 0 + self._low_cmd.motor_cmd[i].tau = 0 + self._low_cmd.crc = self._crc.Crc(self._low_cmd) + self._publisher.Write(self._low_cmd) + logger.info("Sent safe-stop lowcmd (motors disabled)") + except (OSError, RuntimeError, AttributeError) as e: + logger.warning(f"Safe-stop lowcmd failed: {e}") + # Close DDS endpoints explicitly — GC-based cleanup races with in-flight # callbacks and segfaults on process exit (mirrors the Go2 adapter). if self._subscriber is not None: @@ -305,7 +328,16 @@ def _on_motor_command(self, msg: MotorCommandArray) -> None: self._publisher.Write(self._low_cmd) def _release_sport_mode(self) -> None: - """Loop ReleaseMode until MotionSwitcher reports no active controller.""" + """Loop ReleaseMode until MotionSwitcher reports no active controller. + + Bails early if the first CheckMode reports nothing active. That + matters for back-to-back ``dimos run`` invocations: the first run + already released sport mode, so on a clean second start there's + nothing to release. Calling ReleaseMode anyway opens a window + where motor controllers are mid-handoff while we're already + publishing rt/lowcmd, which has been observed to cause horrible + mechanical noise from the gearboxes. + """ from unitree_sdk2py.comm.motion_switcher.motion_switcher_client import ( MotionSwitcherClient, ) @@ -314,8 +346,14 @@ def _release_sport_mode(self) -> None: msc.SetTimeout(5.0) msc.Init() - # CheckMode returns (status, None) once nothing is active — null-tolerant. + # CheckMode returns (status, None) — or (status, {"name": ""}) on + # some firmwares — once nothing is active. Treat both as "already + # released" and return without poking ReleaseMode. _status, result = msc.CheckMode() + if not result or not result.get("name"): + logger.info("Sport mode already released — skipping ReleaseMode") + return + while result and result.get("name"): msc.ReleaseMode() _status, result = msc.CheckMode() From 224e7e91cf50b04e871a98c5d755979d2dbabb15 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 16:59:33 -0700 Subject: [PATCH 20/23] chore(g1-wbc): strip section-marker comments ``dimos/project/test_no_sections.py`` forbids ``# -----`` separator banners and ``# --- text ---`` inline section headers as a project style rule. Three files in this PR carried the pattern from earlier drafts; convert inline-section to plain ``# text`` and drop pure separators. No code-behaviour change. --- dimos/control/tasks/groot_wbc_task.py | 16 ---------------- dimos/hardware/whole_body/mujoco/g1/adapter.py | 4 ---- dimos/simulation/engines/mujoco_shm.py | 4 ++-- 3 files changed, 2 insertions(+), 22 deletions(-) diff --git a/dimos/control/tasks/groot_wbc_task.py b/dimos/control/tasks/groot_wbc_task.py index 5a321b9ddf..22f589c2cb 100644 --- a/dimos/control/tasks/groot_wbc_task.py +++ b/dimos/control/tasks/groot_wbc_task.py @@ -294,10 +294,8 @@ def compute(self, state: CoordinatorState) -> JointCommandOutput | None: pos = state.joints.get_position(jname) current_15[i] = pos if pos is not None else 0.0 - # ------------------------------------------------------------------ # arm() was called — snapshot the ramp start and enter arming / # armed state (ramp=0 arms immediately). - # ------------------------------------------------------------------ if self._arm_pending: self._ramp_start = current_15.copy() self._arming_start_t = state.t_now @@ -315,12 +313,10 @@ def compute(self, state: CoordinatorState) -> JointCommandOutput | None: logger.info(f"GrootWBCTask '{self._name}' armed (no ramp)") self._arm_pending = False - # ------------------------------------------------------------------ # Unarmed & not arming: echo current joint positions. With the # component's kp/kd applied downstream, q_tgt == q_actual yields # pure damping (tau = -kd * dq), which mirrors the reference # backend's inactive "hold current pose" behaviour. - # ------------------------------------------------------------------ if not self._armed and not self._arming: self._last_targets = current_15.tolist() return JointCommandOutput( @@ -329,9 +325,7 @@ def compute(self, state: CoordinatorState) -> JointCommandOutput | None: mode=ControlMode.SERVO_POSITION, ) - # ------------------------------------------------------------------ # Arming: lerp ramp_start → default_15 over arming_duration. - # ------------------------------------------------------------------ if self._arming: assert self._ramp_start is not None elapsed = state.t_now - self._arming_start_t @@ -354,12 +348,10 @@ def compute(self, state: CoordinatorState) -> JointCommandOutput | None: mode=ControlMode.SERVO_POSITION, ) - # ------------------------------------------------------------------ # Armed: run the policy. In dry-run mode we still compute (so # the obs buffer stays hot), but return None so no command goes # downstream. A throttled log line shows what WOULD have been # sent, which is how g1-control-api lets operators verify pre-go. - # ------------------------------------------------------------------ self._tick_count += 1 # Decimation: only run inference every N ticks. Between inference @@ -448,9 +440,7 @@ def on_preempted(self, by_task: str, joints: frozenset[str]) -> None: if joints & self._joint_names_set: logger.warning(f"GrootWBCTask '{self._name}' preempted by {by_task} on {joints}") - # ------------------------------------------------------------------ # Velocity command input - # ------------------------------------------------------------------ def set_velocity_command(self, vx: float, vy: float, yaw_rate: float, t_now: float) -> None: """Set the (vx, vy, yaw_rate) commanded to the policy. @@ -472,9 +462,7 @@ def on_twist(self, msg: Twist, t_now: float) -> bool: ) return True - # ------------------------------------------------------------------ # Lifecycle - # ------------------------------------------------------------------ def start(self) -> None: """Enter the coordinator tick loop. @@ -516,9 +504,7 @@ def stop(self) -> None: self._last_targets = None logger.info(f"GrootWBCTask '{self._name}' stopped") - # ------------------------------------------------------------------ # Arming / dry-run (RPC-callable via coordinator.task_invoke) - # ------------------------------------------------------------------ def arm(self, ramp_seconds: float | None = None) -> bool: """Begin the arming sequence. @@ -589,9 +575,7 @@ def state_snapshot(self) -> dict[str, object]: "arming_duration": self._arming_duration, } - # ------------------------------------------------------------------ # Internal helpers - # ------------------------------------------------------------------ def _reset_policy_state(self) -> None: """Clear inference state — obs history, last action, tick count.""" diff --git a/dimos/hardware/whole_body/mujoco/g1/adapter.py b/dimos/hardware/whole_body/mujoco/g1/adapter.py index 81dad333ba..f288622ef5 100644 --- a/dimos/hardware/whole_body/mujoco/g1/adapter.py +++ b/dimos/hardware/whole_body/mujoco/g1/adapter.py @@ -85,9 +85,7 @@ def __init__( self._shm: ManipShmReader | None = None self._connected = False - # ------------------------------------------------------------------ # Lifecycle - # ------------------------------------------------------------------ def connect(self) -> bool: # Attach with retry — MujocoSimModule may still be starting up. @@ -142,9 +140,7 @@ def disconnect(self) -> None: def is_connected(self) -> bool: return self._connected and self._shm is not None - # ------------------------------------------------------------------ # IO (WholeBodyAdapter protocol) - # ------------------------------------------------------------------ def read_motor_states(self) -> list[MotorState]: if not self._connected or self._shm is None: diff --git a/dimos/simulation/engines/mujoco_shm.py b/dimos/simulation/engines/mujoco_shm.py index 54b63e965d..f1a0fa0dbb 100644 --- a/dimos/simulation/engines/mujoco_shm.py +++ b/dimos/simulation/engines/mujoco_shm.py @@ -261,7 +261,7 @@ def read_gripper_command(self) -> float | None: def read_command_mode(self) -> int: return int(self._control()[CTRL_COMMAND_MODE]) - # --- Whole-body additions --- + # Whole-body additions def write_imu( self, @@ -390,7 +390,7 @@ def write_gripper_command(self, position: float) -> None: arr[1] = position self._increment_seq(SEQ_GRIPPER_CMD) - # --- Whole-body additions --- + # Whole-body additions def read_imu( self, From bbcc777e4ea1fd5980ba5be3a0c6048012d01d19 Mon Sep 17 00:00:00 2001 From: Nabla7 Date: Thu, 7 May 2026 17:19:07 -0700 Subject: [PATCH 21/23] fix(g1-wbc): mypy errors uncovered by full CI-matching env MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * tick_loop.py / groot_wbc_task.py: import the class (``from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped``, same for ``Twist``), not the module — module-as-type tripped mypy ``[valid-type]``. * coordinator.py: when constructing ``GrootWBCTask``, narrow ``hw`` to ``ConnectedWholeBody`` via isinstance before passing ``hw.adapter`` (else mypy unions the manipulator + whole-body adapter types). Also raises a clear TypeError if a non-whole-body component is referenced by a groot_wbc task. * test_unitree_g1_groot_wbc.py: type ``_coordinator_kwargs() -> dict[str, Any]`` so list/iter usages on the values typecheck. ``mypy dimos`` is clean (670 files). --- dimos/control/coordinator.py | 8 ++++++++ dimos/control/tasks/groot_wbc_task.py | 2 +- dimos/control/tick_loop.py | 2 +- .../g1/blueprints/basic/test_unitree_g1_groot_wbc.py | 4 +++- 4 files changed, 13 insertions(+), 3 deletions(-) diff --git a/dimos/control/coordinator.py b/dimos/control/coordinator.py index 64eed4c213..931fb6a5f1 100644 --- a/dimos/control/coordinator.py +++ b/dimos/control/coordinator.py @@ -444,6 +444,8 @@ def _create_task_from_config(self, cfg: TaskConfig) -> ControlTask: ) if cfg.hardware_id is None: raise ValueError(f"GrootWBCTask '{cfg.name}' requires hardware_id in TaskConfig") + from dimos.control.hardware_interface import ConnectedWholeBody + hw = self._hardware.get(cfg.hardware_id) if hw is None: raise ValueError( @@ -451,6 +453,12 @@ def _create_task_from_config(self, cfg: TaskConfig) -> ControlTask: f"'{cfg.hardware_id}'. List the hardware before the task " f"in the blueprint config." ) + if not isinstance(hw, ConnectedWholeBody): + raise TypeError( + f"GrootWBCTask '{cfg.name}' requires a WHOLE_BODY hardware " + f"component for '{cfg.hardware_id}', got " + f"{type(hw).__name__}. Set hardware_type=HardwareType.WHOLE_BODY." + ) model_dir = Path(cfg.model_path) wbc_kwargs: dict[str, Any] = dict( diff --git a/dimos/control/tasks/groot_wbc_task.py b/dimos/control/tasks/groot_wbc_task.py index 22f589c2cb..3f38404bdf 100644 --- a/dimos/control/tasks/groot_wbc_task.py +++ b/dimos/control/tasks/groot_wbc_task.py @@ -48,7 +48,7 @@ from pathlib import Path from dimos.hardware.whole_body.spec import WholeBodyAdapter - from dimos.msgs.geometry_msgs import Twist + from dimos.msgs.geometry_msgs.Twist import Twist logger = setup_logger() diff --git a/dimos/control/tick_loop.py b/dimos/control/tick_loop.py index 4d5a25ced3..6ed2224a21 100644 --- a/dimos/control/tick_loop.py +++ b/dimos/control/tick_loop.py @@ -48,7 +48,7 @@ from dimos.control.components import HardwareId, JointName, TaskName from dimos.control.hardware_interface import ConnectedHardware from dimos.hardware.manipulators.spec import ControlMode - from dimos.msgs.geometry_msgs import PoseStamped + from dimos.msgs.geometry_msgs.PoseStamped import PoseStamped logger = setup_logger() diff --git a/dimos/robot/unitree/g1/blueprints/basic/test_unitree_g1_groot_wbc.py b/dimos/robot/unitree/g1/blueprints/basic/test_unitree_g1_groot_wbc.py index ad3862c4f6..9d99e356a2 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/test_unitree_g1_groot_wbc.py +++ b/dimos/robot/unitree/g1/blueprints/basic/test_unitree_g1_groot_wbc.py @@ -31,6 +31,8 @@ from __future__ import annotations +from typing import Any + from dimos.robot.unitree.g1.blueprints.basic.unitree_g1_groot_wbc import ( unitree_g1_groot_wbc, ) @@ -40,7 +42,7 @@ def _module_names() -> set[str]: return {atom.module.__name__ for atom in unitree_g1_groot_wbc.blueprints} -def _coordinator_kwargs() -> dict: +def _coordinator_kwargs() -> dict[str, Any]: for atom in unitree_g1_groot_wbc.blueprints: if atom.module.__name__ == "ControlCoordinator": return atom.kwargs From 38d6c9158b887500f85ffd048d80aaffd4610017 Mon Sep 17 00:00:00 2001 From: Jeff Hykin Date: Fri, 8 May 2026 17:59:12 -0700 Subject: [PATCH 22/23] - --- .../unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py index cc7f5bbd47..20136afd9d 100644 --- a/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py +++ b/dimos/robot/unitree/g1/blueprints/basic/unitree_g1_groot_wbc_sim.py @@ -57,7 +57,7 @@ # DIMOS_MUJOCO_VIEW=1 subprocess can both open the file regardless of # the shell's CWD. get_data also auto-extracts the LFS tarball on # first run. -_MJCF_PATH = str(get_data("mujoco_sim") / "g1_gear_wbc.xml") +_MJCF_PATH = str(get_data("mujoco_sim/g1_gear_wbc.xml")) _g1_engine = MujocoSimModule.blueprint( address=_MJCF_PATH, From 4aa9d0852bbfcd0093186d8412e496845bc93eec Mon Sep 17 00:00:00 2001 From: Jeff Hykin Date: Fri, 8 May 2026 18:43:39 -0700 Subject: [PATCH 23/23] - --- .../service/system_configurator/libpython.py | 16 +++++++++++++--- 1 file changed, 13 insertions(+), 3 deletions(-) diff --git a/dimos/protocol/service/system_configurator/libpython.py b/dimos/protocol/service/system_configurator/libpython.py index 1aa16f4d3d..82341d79e8 100644 --- a/dimos/protocol/service/system_configurator/libpython.py +++ b/dimos/protocol/service/system_configurator/libpython.py @@ -15,8 +15,14 @@ """Ensure libpython is available in the venv for MuJoCo's mjpython on macOS. When Python is installed via uv, mjpython fails because it expects -libpython at .venv/lib/ but uv places it in its own managed directory. -This configurator creates a symlink so mjpython can find the library. +libpython at a path that uv doesn't populate. mjpython's launcher script +parses @executable_path rpaths from the python binary via otool and +applies os.path.dirname() to each, feeding the results into +DYLD_FALLBACK_LIBRARY_PATH. For uv's cpython build with +``LC_RPATH = @executable_path/../lib``, this buggy dirname computation +resolves to the venv root (``.venv/``), not ``.venv/lib/`` — so that's +where mjpython actually searches. This configurator creates the symlink +at the venv root so the dlopen succeeds. """ from __future__ import annotations @@ -44,10 +50,14 @@ def check(self) -> bool: return True self._missing.clear() - venv_lib = Path(sys.prefix) / "lib" + venv_root = Path(sys.prefix) + venv_lib = venv_root / "lib" real_lib = Path(sys.executable).resolve().parent.parent / "lib" for dylib in real_lib.glob("libpython*.dylib"): + target = venv_root / dylib.name + if not target.exists(): + self._missing.append((target, dylib)) target = venv_lib / dylib.name if not target.exists(): self._missing.append((target, dylib))