diff --git a/robodriver/robots/Universal_Client-master/.github/workflows/test.yml b/robodriver/robots/Universal_Client-master/.github/workflows/test.yml new file mode 100644 index 0000000..c71aaf7 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/.github/workflows/test.yml @@ -0,0 +1,37 @@ +name: "LinkerBot CI" + +on: + push: + branches: [ "main" ] # 每次推送到 main 分支时触发 + pull_request: + branches: [ "main" ] # 提交 PR 时触发 + +jobs: + test_requirements: + runs-on: ubuntu-latest + env: + # 强制使用官方源,防止任何遗留的镜像源配置导致 403 + UV_DEFAULT_INDEX: "https://pypi.org/simple" + steps: + - name: Checkout Code + uses: actions/checkout@v4 + + - name: Install uv + uses: astral-sh/setup-uv@v3 + with: + version: "latest" + enable-cache: true # 开启缓存加速后续构建 + + - name: Set up Python + uses: actions/setup-python@v5 + with: + python-version: "3.10" + + - name: Install Dependencies + run: | + uv sync + + - name: Run Pytest + run: | + # 运行 tests 目录下的所有测试,并输出详细信息 + uv run pytest tests/test.py -v \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/.gitignore b/robodriver/robots/Universal_Client-master/.gitignore new file mode 100644 index 0000000..9c872ef --- /dev/null +++ b/robodriver/robots/Universal_Client-master/.gitignore @@ -0,0 +1,18 @@ +# Python +__pycache__/ +*.py[cod] +*.so +.env +venv/ +*.egg-info/ + +# ROS +build/ +devel/ +logs/ + +# IDE +.vscode/ +.idea/ + +repomix-output.xml \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/.repomixignore b/robodriver/robots/Universal_Client-master/.repomixignore new file mode 100644 index 0000000..021bdcf --- /dev/null +++ b/robodriver/robots/Universal_Client-master/.repomixignore @@ -0,0 +1,9 @@ +# Add patterns to ignore here, one per line +# Example: +# *.log +# tmp/ +.git/ +.venv/ +__pycache__/ +*.egg-info/ +uv.lock diff --git a/robodriver/robots/Universal_Client-master/README.md b/robodriver/robots/Universal_Client-master/README.md new file mode 100644 index 0000000..d5ebe63 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/README.md @@ -0,0 +1,21 @@ +# LinkerBot_Client + +## get start +1. 克隆仓库 +``` +git clone https://github.com/Yaoxing-Technology/LinkerBot_Client.git && cd LinkerBot_Client +``` +2. 安装依赖 +``` +pip install uv +uv sync +``` +3. 启动环境 +``` +source .venv/bin/activate +``` +4. 测试机器人 +``` +python tests/test_robot.py +``` + diff --git a/robodriver/robots/Universal_Client-master/config/settings.yaml b/robodriver/robots/Universal_Client-master/config/settings.yaml new file mode 100644 index 0000000..6d2aea0 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/config/settings.yaml @@ -0,0 +1,101 @@ +app: + name: "LinkerBot-ZMQ-Hub" + middleware: "ros2" # 可选: "ros1", "ros2" + fps: 30 + +zmq: + pub_address: "tcp://0.0.0.0:5577" # 状态广播 + sub_address: "tcp://0.0.0.0:5578" # 控制端广播 + debug: false + +adapter: + pub_address: "tcp://0.0.0.0:6000" # 旧版系统监听的地址 + fps: 30 # 数据采集发送频率 + +# 硬件设备树:已彻底解耦为 sensors(获取) 和 actuators(控制) +devices: + # ========================================== + # Sensors: 用于订阅 ROS 话题并将数据上报给 ZMQ + # ========================================== + sensors: + image_top: + topic: "/camera/color/image_raw" + msg_class: "sensor_msgs.msg.Image" + + # --- 主臂数据源 --- + leader_left_joints: + topic: "/left_arm_joint_control" + msg_class: "sensor_msgs.msg.JointState" + format: "generic" + leader_right_joints: + topic: "/right_arm_joint_control" + msg_class: "sensor_msgs.msg.JointState" + format: "generic" + leader_left_hand: + topic: "/cb_left_hand_raw_data" + msg_class: "sensor_msgs.msg.JointState" + format: "hand" + leader_right_hand: + topic: "/cb_right_hand_raw_data" + msg_class: "sensor_msgs.msg.JointState" + format: "hand" + + # --- 从臂数据源 --- + follower_left_joints: + topic: "/robot1/left_arm/joint_states" + msg_class: "sensor_msgs.msg.JointState" + format: "generic" + follower_left_pose: + topic: "/robot1/left_arm/pose_states" + msg_class: "geometry_msgs.msg.PoseStamped" + format: "pose" + follower_right_joints: + topic: "/robot1/right_arm/joint_states" + msg_class: "sensor_msgs.msg.JointState" + format: "generic" + follower_right_pose: + topic: "/robot1/right_arm/pose_states" + msg_class: "geometry_msgs.msg.PoseStamped" + format: "pose" + + # --- 灵巧手 (支持无名关节的脏数据清洗) --- + follower_left_hand: + topic: "/cb_left_hand_state" + msg_class: "sensor_msgs.msg.JointState" + format: "hand" + follower_right_hand: + topic: "/cb_right_hand_state" + msg_class: "sensor_msgs.msg.JointState" + format: "hand" + + # ========================================== + # Actuators: 用于接收 ZMQ 指令并发布为 ROS 话题 + # ========================================== + actuators: + follower_left_arm_control: + topic: "/robot1/left_arm/joint_follow" + msg_class: "lbot_arm_interfaces.msg.FollowJoint" + format: "generic" + + follower_right_arm_control: + topic: "/robot1/right_arm/joint_follow" + msg_class: "lbot_arm_interfaces.msg.FollowJoint" + format: "generic" + + follower_left_hand_control: + topic: "/cb_left_hand_control_cmd" + msg_class: "sensor_msgs.msg.JointState" + format: "hand" + + follower_right_hand_control: + topic: "/cb_right_hand_control_cmd" + msg_class: "sensor_msgs.msg.JointState" + format: "hand" + +inference: + engine: "beingh" + host: "127.0.0.1" + port: 5800 + + engine_params: + action_chunk_index: 0 \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/pyproject.toml b/robodriver/robots/Universal_Client-master/pyproject.toml new file mode 100644 index 0000000..0027d42 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/pyproject.toml @@ -0,0 +1,35 @@ +[build-system] +requires = ["setuptools>=61.0"] +build-backend = "setuptools.build_meta" + +[project] +name = "universal-client" +version = "0.1.0" +readme = "README.md" +requires-python = ">=3.10,<3.11" + +authors = [ + {name = "yaoxingkeji"}, +] + +dependencies = [ + "numpy<2", + "opencv-python<4.11", + "pyyaml>=6.0.3", + "requests>=2.32.4", + "rospkg>=1.6.0", + "torch>=2.11.0", + "zmq>=0.0.0", +] +[project.scripts] +universal = "src.main:main" + +[tool.setuptools.packages.find] +where = ["."] +include = ["src*"] +namespaces = false + +[dependency-groups] +dev = [ + "pytest>=8.3.5", +] diff --git a/robodriver/robots/Universal_Client-master/repomix.config.json b/robodriver/robots/Universal_Client-master/repomix.config.json new file mode 100644 index 0000000..02d48d9 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/repomix.config.json @@ -0,0 +1,43 @@ +{ + "$schema": "https://repomix.com/schemas/latest/schema.json", + "input": { + "maxFileSize": 52428800 + }, + "output": { + "filePath": "repomix-output.xml", + "style": "xml", + "parsableStyle": false, + "fileSummary": true, + "directoryStructure": true, + "files": true, + "removeComments": false, + "removeEmptyLines": false, + "compress": false, + "topFilesLength": 5, + "showLineNumbers": false, + "truncateBase64": false, + "copyToClipboard": false, + "includeFullDirectoryStructure": false, + "tokenCountTree": false, + "git": { + "sortByChanges": true, + "sortByChangesMaxCommits": 100, + "includeDiffs": false, + "includeLogs": false, + "includeLogsCount": 50 + } + }, + "include": [], + "ignore": { + "useGitignore": true, + "useDotIgnore": true, + "useDefaultPatterns": true, + "customPatterns": [] + }, + "security": { + "enableSecurityCheck": true + }, + "tokenCount": { + "encoding": "o200k_base" + } +} \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/__init__.py b/robodriver/robots/Universal_Client-master/src/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/robodriver/robots/Universal_Client-master/src/api/__init__.py b/robodriver/robots/Universal_Client-master/src/api/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/robodriver/robots/Universal_Client-master/src/api/server.py b/robodriver/robots/Universal_Client-master/src/api/server.py new file mode 100644 index 0000000..708af4c --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/api/server.py @@ -0,0 +1,70 @@ +from fastapi import FastAPI, HTTPException +from pydantic import BaseModel +from typing import List, Optional + +# 引入全新的工厂方法 +from src.core.factory import create_connector +from src.core.base_connector import BaseRobotConnector + +class ControlCommand(BaseModel): + key: str # yaml 里 devices 下的 key,例如 "master_left" + position: List[float] # 目标角度列表 + names: Optional[List[str]] = None # 关节名字 (可选) + +app = FastAPI(title="LinkerBot Edge API") + +# 全局变量存放硬件抽象层实例 +bot: BaseRobotConnector = None + +@app.on_event("startup") +def startup_event(): + """ + FastAPI 启动时,根据 yaml 自动初始化 ROS 1 或 ROS 2 节点 + """ + global bot + try: + bot = create_connector("config/settings.yaml") + bot.start() # 启动底层自旋线程和 ZMQ + print("✅ Robot Connector attached to API Server") + except Exception as e: + print(f"❌ Failed to initialize Robot Connector: {e}") + +@app.on_event("shutdown") +def shutdown_event(): + """优雅释放资源""" + global bot + if bot: + bot.stop() + print("🛑 Robot Connector stopped") + +@app.get("/") +def health_check(): + return {"status": "online", "robot_connected": bot is not None} + +@app.get("/state/{key}") +def get_robot_state(key: str): + if not bot: + raise HTTPException(status_code=503, detail="Robot not connected") + + data = bot.get_state(key) + if data is None: + raise HTTPException(status_code=404, detail=f"Key '{key}' not found or no data yet") + return data + +@app.post("/control") +def send_command(cmd: ControlCommand): + if not bot: + raise HTTPException(status_code=503, detail="Robot not connected") + + # 封装为 dict 传递给底层的 send_control + command_data = { + "position": cmd.position, + "names": cmd.names if cmd.names else [] + } + + success = bot.send_control(cmd.key, command_data) + + if not success: + raise HTTPException(status_code=400, detail="Command failed (check logs or key name)") + + return {"status": "executed", "target": cmd.key} \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/core/__init__.py b/robodriver/robots/Universal_Client-master/src/core/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/robodriver/robots/Universal_Client-master/src/core/base_connector.py b/robodriver/robots/Universal_Client-master/src/core/base_connector.py new file mode 100644 index 0000000..35c53b3 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/core/base_connector.py @@ -0,0 +1,75 @@ +from abc import ABC, abstractmethod +import importlib + +class BaseRobotConnector(ABC): + def __init__(self, config: dict, zmq_hub): + self.config = config + self.zmq_hub = zmq_hub + self.state = {} + self.images = {} + + # --- 新增:动态加载缓存与处理器注册表 --- + self._msg_classes = {} + self._handlers = {} # 格式: { "pkg.msg.Type": {"decode": func, "encode": func} } + + def load_msg_class(self, msg_class_str: str): + """动态反射加载 ROS 消息类""" + if msg_class_str not in self._msg_classes: + module_path, class_name = msg_class_str.rsplit('.', 1) + module = importlib.import_module(module_path) + self._msg_classes[msg_class_str] = getattr(module, class_name) + return self._msg_classes[msg_class_str] + + def register_handler(self, msg_class_str: str, decode_fn=None, encode_fn=None): + """ + 向外暴露的插件注册接口 + :param msg_class_str: 例如 "sensor_msgs.msg.JointState" + :param decode_fn: 用于解析订阅话题数据的函数 + :param encode_fn: 用于封装发布话题数据的函数 + """ + if msg_class_str not in self._handlers: + self._handlers[msg_class_str] = {} + if decode_fn: + self._handlers[msg_class_str]['decode'] = decode_fn + if encode_fn: + self._handlers[msg_class_str]['encode'] = encode_fn + + @abstractmethod + def start(self): + """启动底层的节点/线程""" + pass + + @abstractmethod + def stop(self): + """优雅关闭节点""" + pass + + @abstractmethod + def send_control(self, device_key: str, command_data: dict): + """通用发送控制指令接口""" + pass + + def get_state(self, device_key: str = None): + """获取当前缓存的状态""" + if device_key is None: + return self.state.copy() + return self.state.get(device_key, None) + + def get_image(self, device_key: str): + """获取指定相机的最新 Base64/Raw 图像""" + return self.images.get(device_key, None) + + def _update_and_publish(self, key: str, data: dict): + """内部方法:更新状态并触发 ZMQ 发送""" + self.state[key] = data + if self.zmq_hub: + self.zmq_hub.publish(key, data) + + def _update_and_publish_image(self, key: str, image_bytes: bytes, metadata: dict): + """内部方法:更新缓存并触发 ZMQ 发送""" + self.images[key] = { + "metadata": metadata, + "data": image_bytes + } + if self.zmq_hub: + self.zmq_hub.publish_image(key, image_bytes, metadata) \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/core/connector_ros1.py b/robodriver/robots/Universal_Client-master/src/core/connector_ros1.py new file mode 100644 index 0000000..3b00307 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/core/connector_ros1.py @@ -0,0 +1,109 @@ +import rospy +import time +from src.core.base_connector import BaseRobotConnector + +class ROS1Connector(BaseRobotConnector): + def __init__(self, config: dict, zmq_hub): + super().__init__(config, zmq_hub) + + if not rospy.core.is_initialized(): + rospy.init_node('linkerbot_ros1_hub', disable_signals=True) + + self.subscribers_dict = {} + self.publishers_dict = {} + + if self.zmq_hub: + self.zmq_hub.register_control_callback(self.send_control) + + + def start(self): + rospy.loginfo("🚀 Starting ROS 1 Connector...") + self._auto_wire() + + if self.zmq_hub: + self.zmq_hub.start() + + def stop(self): + rospy.loginfo("🛑 Stopping ROS 1 Connector...") + if self.zmq_hub: + self.zmq_hub.stop() + for sub in self.subscribers_dict.values(): + sub.unregister() + for pub in self.publishers_dict.values(): + pub['pub'].unregister() + rospy.signal_shutdown("System closing") + + def _auto_wire(self): + devices = self.config.get('devices', {}) + + # 1. 挂载 Sensors (Subscribers) + sensors = devices.get('sensors', {}) + for key, meta in sensors.items(): + msg_class_str = meta['msg_class'] + msg_cls = self.load_msg_class(msg_class_str) + sub_topic = meta['topic'] + + # 图像需要大 buffer + queue_size = 1 + buff_size = 65536 * 100 if msg_class_str == "sensor_msgs.msg.Image" else 65536 + + cb = lambda msg, k=key, t=msg_class_str, m=meta: self._generic_sub_cb(msg, k, t, m) + self.subscribers_dict[key] = rospy.Subscriber(sub_topic, msg_cls, cb, queue_size=queue_size, buff_size=buff_size) + rospy.loginfo(f"[AutoWire] SUB: {key} -> {sub_topic} [{msg_class_str}]") + + # 2. 挂载 Actuators (Publishers) + actuators = devices.get('actuators', {}) + for key, meta in actuators.items(): + msg_class_str = meta['msg_class'] + msg_cls = self.load_msg_class(msg_class_str) + pub_topic = meta['topic'] + + self.publishers_dict[key] = { + 'pub': rospy.Publisher(pub_topic, msg_cls, queue_size=10), + 'msg_class_str': msg_class_str, + 'msg_cls': msg_cls, + 'meta': meta + } + rospy.loginfo(f"[AutoWire] PUB: {key} -> {pub_topic} [{msg_class_str}]") + + def _generic_sub_cb(self, msg, key, msg_class_str, meta): + # 图像零拷贝特判 + if msg_class_str == "sensor_msgs.msg.Image": + ts = msg.header.stamp.to_sec() if hasattr(msg, 'header') else time.time() + metadata = { + "width": msg.width, "height": msg.height, "step": msg.step, + "encoding": msg.encoding, "timestamp": ts, "format": "raw" + } + self._update_and_publish_image(key, msg.data, metadata) + return + + handler = self._handlers.get(msg_class_str, {}).get('decode') + if handler: + data = handler(msg, meta) + data["timestamp"] = msg.header.stamp.to_sec() if hasattr(msg, 'header') else time.time() + self._update_and_publish(key, data) + else: + rospy.logwarn(f"No decode handler registered for {msg_class_str}") + + def send_control(self, device_key: str, command_data: dict): + if device_key not in self.publishers_dict: + return False + + pub_info = self.publishers_dict[device_key] + msg_class_str = pub_info['msg_class_str'] + msg_cls = pub_info['msg_cls'] + publisher = pub_info['pub'] + meta = pub_info['meta'] + + handler = self._handlers.get(msg_class_str, {}).get('encode') + if handler: + msg = handler(msg_cls, command_data, meta) + if hasattr(msg, 'header'): + msg.header.stamp = rospy.Time.now() + if not hasattr(msg.header, 'frame_id') or not msg.header.frame_id: + msg.header.frame_id = "base_link" + publisher.publish(msg) + return True + else: + rospy.logerr(f"No encode handler registered for {msg_class_str}") + return False \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/core/connector_ros2.py b/robodriver/robots/Universal_Client-master/src/core/connector_ros2.py new file mode 100644 index 0000000..77b7caf --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/core/connector_ros2.py @@ -0,0 +1,147 @@ +import rclpy +from rclpy.node import Node +from rclpy.executors import MultiThreadedExecutor +from rclpy.callback_groups import ReentrantCallbackGroup +import threading +import time +from src.core.base_connector import BaseRobotConnector + +class ROS2Connector(BaseRobotConnector, Node): + def __init__(self, config: dict, zmq_hub): + # 1. 初始化 ROS 2 基础环境 + if not rclpy.ok(): + rclpy.init() + + # 2. 初始化父类 + BaseRobotConnector.__init__(self, config, zmq_hub) + Node.__init__(self, 'linkerbot_ros2_hub') + + # 3. 并发配置:使用重入回调组 + self.callback_group = ReentrantCallbackGroup() + self.ros_executor = MultiThreadedExecutor(num_threads=8) + self.ros_executor.add_node(self) + + self.subscribers_dict = {} + self.publishers_dict = {} + + # 4. 注册 ZMQ 回调 + if self.zmq_hub: + self.zmq_hub.register_control_callback(self.send_control) + + + + # 5. 定义旋转线程 + self.spin_thread = threading.Thread(target=self._run_executor, daemon=True) + + def _run_executor(self): + try: + self.ros_executor.spin() + except Exception as e: + if rclpy.ok(): + self.get_logger().error(f"ROS 2 Executor Error: {e}") + + def start(self): + self._auto_wire() + + if self.zmq_hub: + self.zmq_hub.start() + self.get_logger().info("🚀 Starting ROS 2 Connector Spin Thread...") + if not self.spin_thread.is_alive(): + self.spin_thread.start() + + def stop(self): + self.get_logger().info("🛑 Stopping ROS 2 Connector...") + if self.zmq_hub: + self.zmq_hub.stop() + + self.ros_executor.shutdown() + self.destroy_node() + if rclpy.ok(): + rclpy.shutdown() + + def _auto_wire(self): + """全新的自动挂载逻辑,区分 sensors 和 actuators""" + devices = self.config.get('devices', {}) + + # 1. 挂载 Sensors (Subscribers) + sensors = devices.get('sensors', {}) + for key, meta in sensors.items(): + msg_class_str = meta['msg_class'] + msg_cls = self.load_msg_class(msg_class_str) + sub_topic = meta['topic'] + + # 使用通用的回调闭包 + cb = lambda msg, k=key, t=msg_class_str, m=meta: self._generic_sub_cb(msg, k, t, m) + self.subscribers_dict[key] = self.create_subscription(msg_cls, sub_topic, cb, 10, callback_group=self.callback_group) + self.get_logger().info(f"[AutoWire] SUB: {key} -> {sub_topic} [{msg_class_str}]") + + # 2. 挂载 Actuators (Publishers) + actuators = devices.get('actuators', {}) + for key, meta in actuators.items(): + msg_class_str = meta['msg_class'] + msg_cls = self.load_msg_class(msg_class_str) + pub_topic = meta['topic'] + + self.publishers_dict[key] = { + 'pub': self.create_publisher(msg_cls, pub_topic, 10, callback_group=self.callback_group), + 'msg_class_str': msg_class_str, + 'msg_cls': msg_cls, + 'meta': meta + } + self.get_logger().info(f"[AutoWire] PUB: {key} -> {pub_topic} [{msg_class_str}]") + + def _generic_sub_cb(self, msg, key, msg_class_str, meta): + """通用的数据接收回调:查表找 Decode Handler""" + + # 特殊处理图像,保证零拷贝性能 + if msg_class_str == "sensor_msgs.msg.Image": + ts = msg.header.stamp.sec + msg.header.stamp.nanosec * 1e-9 if hasattr(msg, 'header') else time.time() + metadata = { + "width": msg.width, "height": msg.height, "step": msg.step, + "encoding": msg.encoding, "timestamp": ts, "format": "raw" + } + self._update_and_publish_image(key, bytes(msg.data), metadata) + return + + handler = self._handlers.get(msg_class_str, {}).get('decode') + if handler: + # 将 msg 和 yaml 里的 meta (比如 format="hand") 一起传给解码器 + data = handler(msg, meta) + # ROS2 时间戳透传 + if hasattr(msg, 'header'): + data["timestamp"] = msg.header.stamp.sec + msg.header.stamp.nanosec * 1e-9 + else: + data["timestamp"] = time.time() + + self._update_and_publish(key, data) + else: + self.get_logger().warn(f"No decode handler registered for {msg_class_str}", throttle_duration_sec=5.0) + + def send_control(self, device_key: str, command_data: dict): + """通用的控制下发逻辑:查表找 Encode Handler""" + if device_key not in self.publishers_dict: + # 静默忽略,因为 ZMQ 可能会收到不是给 ROS 的指令 + return False + + pub_info = self.publishers_dict[device_key] + msg_class_str = pub_info['msg_class_str'] + msg_cls = pub_info['msg_cls'] + publisher = pub_info['pub'] + meta = pub_info['meta'] + + handler = self._handlers.get(msg_class_str, {}).get('encode') + if handler: + # 将原始指令、消息类和配置元数据传给编码器 + msg = handler(msg_cls, command_data, meta) + + # 自动注入时间戳 (如果自定义包有 header 的话) + if hasattr(msg, 'header'): + msg.header.stamp = self.get_clock().now().to_msg() + if not hasattr(msg.header, 'frame_id') or not msg.header.frame_id: + msg.header.frame_id = "base_link" + + publisher.publish(msg) + return True + else: + self.get_logger().error(f"No encode handler registered for {msg_class_str}") + return False \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/core/factory.py b/robodriver/robots/Universal_Client-master/src/core/factory.py new file mode 100644 index 0000000..7f539a7 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/core/factory.py @@ -0,0 +1,32 @@ +from src.utils.config_loader import ConfigLoader +from src.core.zmq_hub import ZmqHub +from src.plugins import std_ros_handlers, lbot_handlers + +def create_connector(config_path="config/settings.yaml"): + config = ConfigLoader(config_path).load() + middleware = config.get('app', {}).get('middleware', 'ros1').lower() + + # 初始化纯 Python 的 ZMQ Hub + zmq_hub = ZmqHub(config) + + if middleware == 'ros1': + print("🔧 Initializing ROS 1 Backend...") + from src.core.connector_ros1 import ROS1Connector + connector = ROS1Connector(config, zmq_hub) + + elif middleware == 'ros2': + print("🔧 Initializing ROS 2 Backend...") + from src.core.connector_ros2 import ROS2Connector + connector = ROS2Connector(config, zmq_hub) + + elif middleware == 'dora': + print("🔧 Initializing Dora-RS Backend...") + raise NotImplementedError("dora-rs support coming soon") + else: + raise ValueError(f"Unknown middleware: {middleware}") + + + std_ros_handlers.register(connector) + lbot_handlers.register(connector) + + return connector \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/core/zmq_hub.py b/robodriver/robots/Universal_Client-master/src/core/zmq_hub.py new file mode 100644 index 0000000..23c7a40 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/core/zmq_hub.py @@ -0,0 +1,125 @@ +import zmq +import json +import threading +import time + +class ZmqHub: + def __init__(self, config: dict): + self.config = config + # --- 新增:Debug 控制参数 --- + self.debug = config.get('zmq', {}).get('debug', True) + self.log_interval = 100 # 高频数据每 100 帧打印一次 + self.pub_count = {} # 用于计数不同 topic 的发送次数 + + self.pub_address = config.get('zmq', {}).get('pub_address', "tcp://0.0.0.0:5555") + self.sub_address = config.get('zmq', {}).get('sub_address', "tcp://0.0.0.0:5556") + + self.context = zmq.Context() + self.send_lock = threading.Lock() + # --- 1. 初始化 Publisher (状态上报) --- + self.publisher = self.context.socket(zmq.PUB) + self.publisher.bind(self.pub_address) + print(f"[ZMQ] 📡 Publisher bound to {self.pub_address}") + + # --- 2. 初始化 Subscriber (接收控制指令) --- + self.subscriber = self.context.socket(zmq.SUB) + self.subscriber.bind(self.sub_address) + self.subscriber.setsockopt_string(zmq.SUBSCRIBE, "") + print(f"[ZMQ] 🎧 Subscriber bound to {self.sub_address}") + + self.running = False + self.control_callback = None + self.sub_thread = None + + def start(self): + self.running = True + self.sub_thread = threading.Thread(target=self._receive_loop, daemon=True) + self.sub_thread.start() + + def stop(self): + self.running = False + self.context.term() + + def publish(self, topic: str, data: dict): + """高速发布状态数据 (统一改为三段式,透传 ROS 时间戳)""" + try: + # 1. 优先获取 ROS 传来的 timestamp,没有则回退到当前系统时间 + ros_ts = data.get("timestamp", time.time()) + + # 2. 构造 Meta,标识这是一个 JSON 数据包 + meta = { + "type": "json", + "timestamp": ros_ts, + "is_image": False # 显式告知接收端这不是图像 + } + + topic_b = topic.encode('utf-8') + meta_b = json.dumps(meta).encode('utf-8') + data_b = json.dumps(data).encode('utf-8') + + with self.send_lock: + self.publisher.send_multipart([topic_b, meta_b, data_b]) + + if self.debug: + self._sampled_log(topic, f"Sending State [TS: {ros_ts}] -> {data}") + + except Exception as e: + if self.debug: print(f"[ZMQ PUB Error] {e}") + + def publish_image(self, topic: str, image_bytes: bytes, metadata: dict): + """发送二进制图像数据 (使用 ROS 传入的 metadata)""" + try: + # metadata 已经在 ROS2Connector 中包含了 ROS 的 timestamp + ros_ts = metadata.get("timestamp", time.time()) + + # 为了方便 Adapter 识别,确保 metadata 里有 is_image 标记 + metadata["is_image"] = True + + topic_b = topic.encode('utf-8') + meta_b = json.dumps(metadata).encode('utf-8') + + # 发送 3 段:[Topic, Meta, Bytes] + with self.send_lock: + self.publisher.send_multipart([topic_b, meta_b, image_bytes]) + + if self.debug: + log_msg = f"Sending Image [TS: {ros_ts}] | DataSize: {len(image_bytes)/1024:.2f} KB" + self._sampled_log(topic, log_msg) + + except Exception as e: + if self.debug: print(f"[ZMQ IMG Error] {e}") + + def register_control_callback(self, callback_func): + self.control_callback = callback_func + + def _receive_loop(self): + """接收 ZMQ 控制指令""" + while self.running: + try: + events = self.subscriber.poll(100) + if events: + msg = self.subscriber.recv_string() + payload = json.loads(msg) + + # --- 新增:控制指令 Log (指令通常低频,建议全量打印) --- + if self.debug: + print(f" \033[92m[ZMQ RECV]\033[0m Topic: {payload.get('device_key')} | Command: {payload.get('command')}") + + device_key = payload.get("device_key") + command = payload.get("command") + + if device_key and command and self.control_callback: + self.control_callback(device_key, command) + except Exception as e: + if self.running: + print(f"[ZMQ] Error receiving control: {e}") + time.sleep(0.02) + + # --- 工具方法:采样打印防止刷屏 --- + def _sampled_log(self, topic: str, message: str): + if topic not in self.pub_count: + self.pub_count[topic] = 0 + self.pub_count[topic] += 1 + + if self.pub_count[topic] % self.log_interval == 0: + print(f"[ZMQ PUB Sampling][{topic}] {message}") \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/inference/__init__.py b/robodriver/robots/Universal_Client-master/src/inference/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/robodriver/robots/Universal_Client-master/src/inference/cloud_agent.py b/robodriver/robots/Universal_Client-master/src/inference/cloud_agent.py new file mode 100644 index 0000000..10882a1 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/inference/cloud_agent.py @@ -0,0 +1,73 @@ +import time +from collections import deque +from src.core.factory import create_connector +from src.inference.factory import create_inference_engine + +class CloudInferenceAgent: + def __init__(self, config): + self.config = config + + # 1. 启动硬件抽象层 (底层数据采集与下发) + self.robot = create_connector("config/settings.yaml") + self.robot.start() + print("✅ Robot Connector attached.") + + # 2. 启动推理引擎 (这里就是调用了刚才的工厂模式,根据 YAML 自动生成 BeingH 插件) + self.engine = create_inference_engine(config) + print(f"✅ Inference Engine initialized.") + + self.fps = config.get('app', {}).get('fps', 10) + self.sleep_time = 1.0 / self.fps + + # 你的语言指令 + self.current_instruction = "pick up the red apple on the table" + self.action_queue = deque() + self.replan_threshold = 6 # 剩余多少帧就开始重新规划 + def run(self): + print("🤖 VLA Control Loop is running...") + try: + while True: + step_start = time.time() + self._step() + + # 严格控制控制频率 (例如 10Hz) + elapsed = time.time() - step_start + if elapsed < self.sleep_time: + time.sleep(self.sleep_time - elapsed) + except KeyboardInterrupt: + print("\n🛑 Agent stopped by user.") + finally: + self.robot.stop() + + def _step(self): + # 1. 只有在队列快空了的时候,我们才需要去取图像并调用大模型(节省算力和网络带宽) + if len(self.action_queue) <= self.replan_threshold: + raw_states = { + "follower_left_joints": self.robot.get_state("follower_left_joints"), + "follower_left_pose": self.robot.get_state("follower_left_pose"), + "follower_left_hand": self.robot.get_state("follower_left_hand"), + "image_top": self.robot.get_image("image_top") + } + + if raw_states["follower_left_joints"]: + try: + # 这时候拿到的不再是一个字典,而是一个包含了 16 个字典的列表 + actions_chunk = self.engine.predict(raw_states, self.current_instruction) + + if actions_chunk: + # [Receding Horizon 策略]:直接清空旧的剩余动作,用大模型最新的视觉预测覆盖 + self.action_queue.clear() + self.action_queue.extend(actions_chunk) + except Exception as e: + print(f"⚠️ Inference error: {e}") + + # 2. 如果队列里有动作,就开始出队并发送给硬件 + if len(self.action_queue) > 0: + # 弹出最早的一个动作 + current_action = self.action_queue.popleft() + + # 分发控制指令 (例如 left_arm 和 left_hand) + for device_key, command_data in current_action.items(): + self.robot.send_control(device_key, command_data) + + print(f"⚡ [Execution] Executed 1 step. Queue remaining: {len(self.action_queue)}") \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/inference/data_collector_adapter.py b/robodriver/robots/Universal_Client-master/src/inference/data_collector_adapter.py new file mode 100644 index 0000000..20eb224 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/inference/data_collector_adapter.py @@ -0,0 +1,189 @@ +#!/usr/bin/env python3 +import zmq +import json +import pickle +import time +import threading +import numpy as np +import cv2 + +class DataCollectionAdapter: + def __init__(self, config: dict): + """传入统一的 yaml 配置""" + self.config = config + self.ctx = zmq.Context.instance() + + # 1. 自动解析配置 + # ZMQ Hub 绑定的是 0.0.0.0,但我们作为订阅端连接时,需要连 127.0.0.1 + hub_bind_addr = config.get('zmq', {}).get('pub_address', "tcp://0.0.0.0:5555") + hub_sub_address = hub_bind_addr.replace("0.0.0.0", "127.0.0.1") + + legacy_pub_address = config.get('adapter', {}).get('pub_address', "tcp://0.0.0.0:6000") + self.fps = config.get('adapter', {}).get('fps', 30.0) + + # 2. 初始化 Sockets + self.sub_socket = self.ctx.socket(zmq.SUB) + self.sub_socket.connect(hub_sub_address) + self.sub_socket.setsockopt_string(zmq.SUBSCRIBE, "") + + self.pub_socket = self.ctx.socket(zmq.PUB) + self.pub_socket.bind(legacy_pub_address) + + self.running = False + self.state_cache = {} + self.lock = threading.Lock() + + print(f"🚀 Unified Adapter Ready: [SUB {hub_sub_address}] -> [PUB {legacy_pub_address}] @ {self.fps} Hz") + + def start(self): + """由外部主程序调用启动""" + if self.running: + return + self.running = True + self.recv_thread = threading.Thread(target=self._recv_loop, daemon=True) + self.send_thread = threading.Thread(target=self._send_loop, kwargs={"hz": self.fps}, daemon=True) + self.recv_thread.start() + self.send_thread.start() + print("✅ Data Collection Adapter started.") + + def stop(self): + """安全停止""" + self.running = False + # 不强制 close socket,让 context 自动回收或进程退出时回收,防止阻塞 + print("🛑 Data Collection Adapter stopped.") + + def _recv_loop(self): + """严谨的 3 段式接收,防止 Topic 和 Meta 倒置""" + while self.running: + try: + parts = self.sub_socket.recv_multipart() + if len(parts) != 3: continue + + # 确保 Topic 是字符串 + topic = parts[0].decode('utf-8') + # 确保 Meta 是字典 + try: + meta = json.loads(parts[1].decode('utf-8')) + except: continue + + raw_payload = parts[2] + + with self.lock: + # 关键修复:使用显式标签区分类型 + if meta.get("is_image") is True: + self.state_cache[topic] = { + "_type": "image", + "meta": meta, + "bytes": bytes(raw_payload) + } + else: + try: + json_data = json.loads(raw_payload.decode('utf-8')) + # 注入时间戳 + json_data["_timestamp"] = meta.get("timestamp", time.time()) + json_data["_type"] = "json" + self.state_cache[topic] = json_data + except: pass + except Exception as e: + if self.running: print(f"❌ Recv Error: {e}") + + def _send_loop(self, hz=30.0): + period = 1.0 / hz + while self.running: + loop_start = time.time() + with self.lock: + items = list(self.state_cache.items()) + + for comp_name, data in items: + try: + # 跳过无效数据 + if not isinstance(data, dict) or "_type" not in data: continue + + payload = None + ros_ts = data.get("_timestamp", time.time()) + + if data["_type"] == "image": + meta = data.get("meta", {}) + raw_bytes = data["bytes"] + frame = None + + try: + # 分流处理:Raw 格式 (通常来自 ROS Camera 驱动) + if meta.get("format") == "raw" or meta.get("encoding") == "rgb8": + # 从二进制 buffer 恢复 [H, W, C] 矩阵 + h = meta.get("height", 480) + w = meta.get("width", 640) + # 恢复为 numpy 数组 + frame = np.frombuffer(raw_bytes, dtype=np.uint8).reshape(h, w, 3) + + # 颜色转换:ROS 默认 RGB,但 OpenCV/Node.py 通常使用 BGR + if meta.get("encoding") == "rgb8": + frame = cv2.cvtColor(frame, cv2.COLOR_RGB2BGR) + + # 分流处理:压缩格式 (JPEG, PNG) + else: + img_np = np.frombuffer(raw_bytes, dtype=np.uint8) + frame = cv2.imdecode(img_np, cv2.IMREAD_COLOR) + + if frame is not None: + payload = { + "kind": "camera", + "name": comp_name, + "frame": frame, + "timestamp": ros_ts # 优先使用透传的 ROS 时间戳 + } + else: + print(f"⚠️ Warning: Decoded frame is None for {comp_name}") + + except Exception as e: + print(f"❌ Image Reshape/Decode Error on [{comp_name}]: {e}") + + # --- 2. 状态/位姿处理 --- + elif data["_type"] == "json": + # 自动判断:是 Pose 还是 Joint + if "position" in data and isinstance(data["position"], dict): + # --- 核心修复:处理嵌套字典的 Pose (XYZ + Q) --- + pos = data["position"] + ori = data.get("orientation", {}) + + # 显式提取,确保顺序固定为 [x, y, z, qx, qy, qz, qw] + pos_list = [pos.get('x', 0.0), pos.get('y', 0.0), pos.get('z', 0.0)] + ori_list = [ori.get('x', 0.0), ori.get('y', 0.0), ori.get('z', 0.0), ori.get('w', 1.0)] + + pos_values = pos_list + ori_list + kind_suffix = "pose" + else: + # 处理普通列表格式的 Joint + pos_values = data.get("position", []) + kind_suffix = "joint" + + if pos_values: + prefix = "leader" if any(x in comp_name.lower() for x in ["master", "leader", "hp"]) else "follower" + payload = { + "kind": f"{prefix}_{kind_suffix}", + "name": comp_name, + "values": np.array(pos_values, dtype=np.float32), + "timestamp": ros_ts + } + + if payload: + wire = pickle.dumps(payload, protocol=pickle.HIGHEST_PROTOCOL) + self.pub_socket.send_multipart([comp_name.encode(), wire]) + + except Exception as e: + # 增加 Topic 打印,方便定位具体哪个传感器坏了 + print(f"⚠️ Send Error on [{comp_name}]: {e}") + + elapsed = time.time() - loop_start + if elapsed < period: + time.sleep(period - elapsed) + +if __name__ == "__main__": + adapter = DataCollectionAdapter() + try: + while True: + # time.sleep(5) + # print(f"📊 Active Topics: {list(adapter.state_cache.keys())}") + pass + except KeyboardInterrupt: + adapter.running = False \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/inference/factory.py b/robodriver/robots/Universal_Client-master/src/inference/factory.py new file mode 100644 index 0000000..d43b04a --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/inference/factory.py @@ -0,0 +1,24 @@ +from src.inference.registry import get_engine_class + +# 👇 显式导入插件模块,触发里面的 @register_engine 装饰器执行 +import src.inference.plugins.BeingH.beingh_plugin +# import src.inference.plugins.octo_plugin <- 以后有新模型,就加一行 import + +def create_inference_engine(config: dict): + engine_name = config.get('inference', {}).get('engine', 'none').lower() + + # 动态从注册表中获取类 + engine_cls = get_engine_class(engine_name) + + if engine_cls: + # 实例化并返回 + return engine_cls(config) + + elif engine_name == 'none': + # 提供一个空跑的 Dummy,防止报错 + class DummyEngine: + def predict(self, raw_states, instruction): return {} + return DummyEngine() + + else: + raise ValueError(f"❌ 找不到推理引擎插件 '{engine_name}'。请检查 yaml 配置或是否正确导入了对应的 plugin。") \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/inference/plugins/BeingH/__init__.py b/robodriver/robots/Universal_Client-master/src/inference/plugins/BeingH/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/robodriver/robots/Universal_Client-master/src/inference/plugins/BeingH/beingh_plugin.py b/robodriver/robots/Universal_Client-master/src/inference/plugins/BeingH/beingh_plugin.py new file mode 100644 index 0000000..72aa083 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/inference/plugins/BeingH/beingh_plugin.py @@ -0,0 +1,124 @@ +import numpy as np +import cv2 + +# 引入我们刚刚写的注册器 +from src.inference.registry import register_engine + +from .beingh_service import BeingHInferenceClient + +# 👇 神奇的装饰器,直接把这个类注册为 'beingh' +@register_engine("beingh") +class BeingHInferenceAdapter: + def __init__(self, config): + + inf_cfg = config.get('inference', {}) + self.host = inf_cfg.get('host', '127.0.0.1') + self.port = inf_cfg.get('port', 5555) + + # 👇 严格只读取专属配置,避免污染 + kwargs = inf_cfg.get('engine_params', {}) + self.chunk_index = kwargs.get('action_chunk_index', 0) + + print(f"🚀 [Plugin] 正在连接 BeingH 模型服务器 tcp://{self.host}:{self.port}...") + self.client = BeingHInferenceClient(host=self.host, port=self.port) + if not self.client.ping(): + raise ConnectionError("无法连接到 BeingH 推理服务器!") + + def _convert_image(self, img_data): + """处理底层传来的图像字典,转为 NumPy""" + if not img_data: + return np.zeros((640, 480, 3), dtype=np.uint8) + + meta = img_data['metadata'] + raw_bytes = img_data['data'] + h, w = meta.get("height", 480), meta.get("width", 640) + + if meta.get("encoding") == "rgb8" or meta.get("format") == "raw": + return np.frombuffer(raw_bytes, dtype=np.uint8).reshape(h, w, 3) + else: + frame = cv2.imdecode(np.frombuffer(raw_bytes, dtype=np.uint8), cv2.IMREAD_COLOR) + return cv2.cvtColor(frame, cv2.COLOR_BGR2RGB) + + def predict(self, raw_states: dict, instruction: str) -> dict: + """ + 核心接口:接收全量原始状态 -> 转换为模型所需 observations -> 推理 -> 解析并返回通用控制指令 + """ + # 1. 安全提取各部件状态 + l_joints = raw_states.get("follower_left_joints", {}).get("position", [0.0]*7) + l_hand = raw_states.get("follower_left_hand", {}).get("position", [0.0]*10) + + # 解析 Pose (ROS 格式分解为 pos 和 ori) + l_pose_dict = raw_states.get("follower_left_pose", {}) + l_pos = l_pose_dict.get("position", {"x":0.0, "y":0.0, "z":0.0}) + l_ori = l_pose_dict.get("orientation", {"x":0.0, "y":0.0, "z":0.0, "w":1.0}) + + l_pos_arr = [l_pos['x'], l_pos['y'], l_pos['z']] + l_ori_arr = [l_ori['x'], l_ori['y'], l_ori['z'], l_ori['w']] # 四元数 + + top_img = self._convert_image(raw_states.get("image_top")) + + # 2. 严格对齐 LinkerBotLeftOnlyDataConfig 的 STATE_KEYS + observations = { + # 图像:从 (H, W, C) 变为 (1, H, W, C) + "video.head": top_img[None, ...], + + # 状态向量:从 (D,) 变为 (1, D) + "state.left_arm_joint_positions": np.array(l_joints, dtype=np.float32)[None, :], + "state.left_hand_qpos": np.array(l_hand, dtype=np.float32)[None, :], + "state.left_arm_eef_position": np.array(l_pos_arr, dtype=np.float32)[None, :], + "state.left_eef_rotation": np.array(l_ori_arr, dtype=np.float32)[None, :], + + "language.instruction": instruction, # 字符串通常不需要处理,服务端会自行 tokenize + } + + # ========= [DEBUG 打印发送数据] ========= + print("\n\033[96m" + "="*50) + print("📤 发送给 Being-H 的 Observations:") + print(f" - 图像形状: {observations['video.head'].shape}") + print(f" - 关节输入: {np.round(observations['state.left_arm_joint_positions'], 3).tolist()}") + print(f" - 末端位置: {np.round(observations['state.left_arm_eef_position'], 3).tolist()}") + print(f" - 灵巧手输入: {np.round(observations['state.left_hand_qpos'], 3).tolist()}") + print("="*50 + "\033[0m") + + # 3. 发起推理 + result = self.client.get_action(observations) + if not result: + print("⚠️ Server returned empty result!") + return [] # 注意这里返回空列表 + + # 4. 解析结果 + l_arm_chunk = np.array(result.get("action.left_arm_joint_positions", [])) + l_hand_chunk = np.array(result.get("action.left_hand_qpos", [])) + + # 去掉 Batch 维度 (1, 16, D) -> (16, D) + if len(l_arm_chunk) > 0: l_arm_chunk = np.squeeze(l_arm_chunk) + if len(l_hand_chunk) > 0: l_hand_chunk = np.squeeze(l_hand_chunk) + + print(f"🔍 Received raw action chunks: Arm={len(l_arm_chunk)} steps, Hand={len(l_hand_chunk)} steps") + + # 5. 将这 16 帧组装成一个列表 + action_chunk_list = [] + + # 假设 arm 和 hand 的 chunk 长度一致 + chunk_size = min(len(l_arm_chunk), len(l_hand_chunk)) if len(l_arm_chunk) > 0 else 0 + + for i in range(chunk_size): + step_action = {} + + # --- 机械臂 --- + step_action["follower_left_arm_control"] = { + "position": l_arm_chunk[i].tolist(), + "follow": True + } + + # --- 灵巧手 (映射 0-255) --- + raw_hand_action = l_hand_chunk[i][:10] + mapped_hand = np.clip(raw_hand_action * 255.0, 0, 255) + step_action["follower_left_hand_control"] = { + "position": [float(int(x)) for x in mapped_hand], + } + + action_chunk_list.append(step_action) + + print(f"✅ Parsed a chunk of {len(action_chunk_list)} actions.") + return action_chunk_list # 返回整个列表 \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/inference/plugins/BeingH/beingh_service.py b/robodriver/robots/Universal_Client-master/src/inference/plugins/BeingH/beingh_service.py new file mode 100644 index 0000000..54280a5 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/inference/plugins/BeingH/beingh_service.py @@ -0,0 +1,114 @@ +# Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. +# Copyright (c) 2026 BeingBeyond Ltd. and/or its affiliates. +# SPDX-License-Identifier: Apache-2.0 + + + +from typing import Any, Dict, Optional +from .service import BaseInferenceClient, BaseInferenceServer + + +# ============================================================================== +# Server +# ============================================================================== + +class BeingHInferenceServer(BaseInferenceServer): + """ + Inference server for Being-H VLA policy. + + Exposes endpoints for: + - get_action: Action inference from observations + - get_modality_config: Query policy modality configuration + """ + + def __init__( + self, + policy: Any, + host: str = "*", + port: int = 5555, + api_token: Optional[str] = None + ): + """ + Initialize inference server. + + Args: + policy: Policy object with get_action() and get_modality_config() methods + host: Host address to bind (default: "*" for all interfaces) + port: Port to listen on (default: 5555) + api_token: Optional API token for authentication + + Example: + >>> from BeingH.inference.policy import InternVLPolicy + >>> policy = InternVLPolicy(model_path="path/to/model", ...) + >>> server = BeingHInferenceServer(policy, port=5555) + >>> server.start() + """ + + super().__init__(host, port, api_token) + + # Register policy endpoints + self.register_endpoint("get_action", policy.get_action) + self.register_endpoint("get_modality_config", policy.get_modality_config) + + +# ============================================================================== +# Client +# ============================================================================== + +class BeingHInferenceClient(BaseInferenceClient): + """ + Client for calling remote Being-H inference server. + + Provides methods to: + - Query action predictions from observations + - Retrieve policy configuration + """ + + def __init__( + self, + host: str = "localhost", + port: int = 5555, + api_token: Optional[str] = None + ): + """ + Initialize inference client. + + Args: + host: Server hostname (default: "localhost") + port: Server port (default: 5555) + api_token: Optional API token for authentication + + Example: + >>> client = BeingHInferenceClient(host="192.168.1.100", port=5555) + >>> actions = client.get_action(observations) + """ + super().__init__(host=host, port=port, api_token=api_token) + + def get_action(self, observations: Dict[str, Any]) -> Dict[str, Any]: + """ + Get action prediction from remote server. + + Args: + observations: Observation dictionary containing: + - Video frames (RGB images) + - Robot state (joint positions, etc.) + - Task instruction (natural language) + - Optional: prev_chunk and inference_delay for RTC mode + + Returns: + Action dictionary with predicted actions: + - Keys depend on policy configuration + - For RTC mode, includes 'action_unified' for next query + + Example: + >>> observations = { + ... 'video.front_camera': np.array(...), # (H, W, 3) + ... 'state.joint_position': np.array(...), # (7,) + ... 'instruction': ["Pick up the red cube"] + ... } + >>> actions = client.get_action(observations) + >>> print(actions['action.joint_position']) # [[...], [...], ...] + """ + + print(f"📞 Calling 'get_action' on server {self.host}:{self.port}") + return self.call_endpoint("get_action", observations) \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/inference/plugins/BeingH/service.py b/robodriver/robots/Universal_Client-master/src/inference/plugins/BeingH/service.py new file mode 100644 index 0000000..3fd46a4 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/inference/plugins/BeingH/service.py @@ -0,0 +1,193 @@ +# Copyright (c) 2025 NVIDIA CORPORATION & AFFILIATES. +# Copyright (c) 2026 BeingBeyond Ltd. and/or its affiliates. +# SPDX-License-Identifier: Apache-2.0 + +from dataclasses import dataclass +from io import BytesIO +from typing import Any, Callable, Dict + +import torch +import zmq + + +class TorchSerializer: + @staticmethod + def to_bytes(data: dict) -> bytes: + buffer = BytesIO() + torch.save(data, buffer) + return buffer.getvalue() + + @staticmethod + def from_bytes(data: bytes) -> dict: + buffer = BytesIO(data) + obj = torch.load(buffer, weights_only=False) + return obj + + +@dataclass +class EndpointHandler: + handler: Callable + requires_input: bool = True + + +class BaseInferenceServer: + """ + An inference server that spin up a ZeroMQ socket and listen for incoming requests. + Can add custom endpoints by calling `register_endpoint`. + """ + + def __init__(self, host: str = "*", port: int = 5555, api_token: str = None): + self.running = True + self.context = zmq.Context() + self.socket = self.context.socket(zmq.REP) + self.socket.bind(f"tcp://{host}:{port}") + self._endpoints: dict[str, EndpointHandler] = {} + self.api_token = api_token + + # Register the ping endpoint by default + self.register_endpoint("ping", self._handle_ping, requires_input=False) + self.register_endpoint("kill", self._kill_server, requires_input=False) + + def _kill_server(self): + """ + Kill the server. + """ + self.running = False + + def _handle_ping(self) -> dict: + """ + Simple ping handler that returns a success message. + """ + return {"status": "ok", "message": "Server is running"} + + def register_endpoint(self, name: str, handler: Callable, requires_input: bool = True): + """ + Register a new endpoint to the server. + + Args: + name: The name of the endpoint. + handler: The handler function that will be called when the endpoint is hit. + requires_input: Whether the handler requires input data. + """ + self._endpoints[name] = EndpointHandler(handler, requires_input) + + def _validate_token(self, request: dict) -> bool: + """ + Validate the API token in the request. + """ + if self.api_token is None: + return True # No token required + return request.get("api_token") == self.api_token + + def run(self): + addr = self.socket.getsockopt_string(zmq.LAST_ENDPOINT) + print(f"Server is ready and listening on {addr}") + while self.running: + try: + message = self.socket.recv() + request = TorchSerializer.from_bytes(message) + + # Validate token before processing request + if not self._validate_token(request): + self.socket.send( + TorchSerializer.to_bytes({"error": "Unauthorized: Invalid API token"}) + ) + continue + + endpoint = request.get("endpoint", "get_action") + + if endpoint not in self._endpoints: + raise ValueError(f"Unknown endpoint: {endpoint}") + + handler = self._endpoints[endpoint] + result = ( + handler.handler(request.get("data", {})) + if handler.requires_input + else handler.handler() + ) + self.socket.send(TorchSerializer.to_bytes(result)) + except Exception as e: + print(f"Error in server: {e}") + import traceback + + print(traceback.format_exc()) + self.socket.send(TorchSerializer.to_bytes({"error": str(e)})) + + +class BaseInferenceClient: + def __init__( + self, + host: str = "localhost", + port: int = 5555, + timeout_ms: int = 15000, + api_token: str = None, + ): + self.context = zmq.Context() + self.host = host + self.port = port + self.timeout_ms = timeout_ms + self.api_token = api_token + self._init_socket() + + def _init_socket(self): + """Initialize or reinitialize the socket with current settings""" + self.socket = self.context.socket(zmq.REQ) + self.socket.connect(f"tcp://{self.host}:{self.port}") + + def ping(self) -> bool: + try: + self.call_endpoint("ping", requires_input=False) + return True + except zmq.error.ZMQError: + self._init_socket() # Recreate socket for next attempt + return False + + def kill_server(self): + """ + Kill the server. + """ + self.call_endpoint("kill", requires_input=False) + + def call_endpoint( + self, endpoint: str, data: dict | None = None, requires_input: bool = True + ) -> dict: + """ + Call an endpoint on the server. + + Args: + endpoint: The name of the endpoint. + data: The input data for the endpoint. + requires_input: Whether the endpoint requires input data. + """ + request: dict = {"endpoint": endpoint} + if requires_input: + request["data"] = data + if self.api_token: + request["api_token"] = self.api_token + + self.socket.send(TorchSerializer.to_bytes(request)) + message = self.socket.recv() + response = TorchSerializer.from_bytes(message) + + if "error" in response: + raise RuntimeError(f"Server error: {response['error']}") + return response + + def __del__(self): + """Cleanup resources on destruction""" + self.socket.close() + self.context.term() + + +class ExternalRobotInferenceClient(BaseInferenceClient): + """ + Client for communicating with the RealRobotServer + """ + + def get_action(self, observations: Dict[str, Any]) -> Dict[str, Any]: + """ + Get the action from the server. + The exact definition of the observations is defined + by the policy, which contains the modalities configuration. + """ + return self.call_endpoint("get_action", observations) \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/inference/registry.py b/robodriver/robots/Universal_Client-master/src/inference/registry.py new file mode 100644 index 0000000..c8e5834 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/inference/registry.py @@ -0,0 +1,15 @@ +# 统一管理所有推理引擎的字典 +_INFERENCE_ENGINES = {} + +def register_engine(name: str): + """ + 类装饰器:用于将具体的推理引擎类注册到系统中 + 用法: @register_engine("beingh") + """ + def decorator(cls): + _INFERENCE_ENGINES[name.lower()] = cls + return cls + return decorator + +def get_engine_class(name: str): + return _INFERENCE_ENGINES.get(name.lower()) \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/main.py b/robodriver/robots/Universal_Client-master/src/main.py new file mode 100644 index 0000000..c0cab96 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/main.py @@ -0,0 +1,80 @@ +# src/main.py +import sys +import os +import time +import argparse +from src.utils.config_loader import ConfigLoader +from src.inference.cloud_agent import CloudInferenceAgent +from src.inference.data_collector_adapter import DataCollectionAdapter +from src.core.factory import create_connector # 引入底层连接器工厂 + +def main(): + # 1. 设置命令行参数 + parser = argparse.ArgumentParser(description="LinkerBot Edge Node") + parser.add_argument( + '--collect', + action='store_true', + help='启动数据采集旁路 (Data Collection Adapter)' + ) + parser.add_argument( + '--inference', + action='store_true', + help='启动云端/本地推理控制 (Cloud Inference Agent)' + ) + args = parser.parse_args() + + # 安全检查:至少启动一个功能 + if not args.collect and not args.inference: + print("⚠️ 请至少指定一种运行模式: --collect 或 --inference (也可两者同时使用)") + parser.print_help() + return + + # 2. 加载配置 + try: + config = ConfigLoader("config/settings.yaml").load() + except Exception as e: + print(f"❌ Config Error: {e}") + return + + collect_adapter = None + agent = None + robot = None # 用于在无 inference 模式下保持底层存活 + + try: + # 3. 如果需要采集数据,启动采集旁路 + if args.collect: + print("📊 启动数据采集模块...") + collect_adapter = DataCollectionAdapter(config) + collect_adapter.start() + + # 4. 根据是否开启推理,决定程序的运行主轴 + if args.inference: + print("🤖 启动推理控制引擎 (将自动拉起底层硬件)...") + agent = CloudInferenceAgent(config) + # run() 是死循环,阻塞主线程 + agent.run() + else: + # 如果没有启动 agent,说明没有人拉起底层 ROS/ZMQ 连接 + # 这里必须手动拉起底层连接,否则 collect 收集不到任何数据 + print("⚙️ 仅采集模式,初始化并拉起底层硬件连接...") + robot = create_connector("config/settings.yaml") + robot.start() + + print("✅ 系统就绪,正在持续采集数据 (按 Ctrl+C 退出)...") + # 保持主线程存活 + while True: + time.sleep(1) + + except KeyboardInterrupt: + print("\n🛑 收到退出信号,正在优雅关闭所有组件...") + except Exception as e: + print(f"❌ 运行期发生致命错误: {e}") + finally: + # 5. 安全释放所有资源 + if collect_adapter: + collect_adapter.stop() + if robot: + robot.stop() + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/plugins/__init__.py b/robodriver/robots/Universal_Client-master/src/plugins/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/robodriver/robots/Universal_Client-master/src/plugins/lbot_handlers.py b/robodriver/robots/Universal_Client-master/src/plugins/lbot_handlers.py new file mode 100644 index 0000000..94d40d4 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/plugins/lbot_handlers.py @@ -0,0 +1,15 @@ +def encode_follow_joint(msg_cls, command_data, meta): + """ + 专门为 lbot_arm_interfaces.msg.FollowJoint 写的打包逻辑 + """ + msg = msg_cls() + msg.joints = [float(x) for x in command_data.get('position', [])] + msg.follow = command_data.get('follow', True) + return msg + +def register(connector): + """将自定义 Handler 挂载到 connector""" + connector.register_handler( + "lbot_arm_interfaces.msg.FollowJoint", + encode_fn=encode_follow_joint + ) \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/plugins/std_ros_handlers.py b/robodriver/robots/Universal_Client-master/src/plugins/std_ros_handlers.py new file mode 100644 index 0000000..fbed0af --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/plugins/std_ros_handlers.py @@ -0,0 +1,44 @@ +def decode_joint_state(msg, meta): + return { + "name": list(msg.name), + "position": list(msg.position), + "velocity": list(msg.velocity) if msg.velocity else [] + } + +def encode_joint_state(msg_cls, command_data, meta): + msg = msg_cls() + msg.name = meta.get('joint_names', command_data.get('names', [])) + msg.position = [float(x) for x in command_data.get('position', [])] + return msg + +def decode_pose_stamped(msg, meta): + return { + "position": {"x": msg.pose.position.x, "y": msg.pose.position.y, "z": msg.pose.position.z}, + "orientation": {"x": msg.pose.orientation.x, "y": msg.pose.orientation.y, "z": msg.pose.orientation.z, "w": msg.pose.orientation.w} + } + +def encode_pose_stamped(msg_cls, command_data, meta): + msg = msg_cls() + raw_data = command_data.get('position', []) + if len(raw_data) >= 7: + msg.pose.position.x = float(raw_data[0]) + msg.pose.position.y = float(raw_data[1]) + msg.pose.position.z = float(raw_data[2]) + msg.pose.orientation.x = float(raw_data[3]) + msg.pose.orientation.y = float(raw_data[4]) + msg.pose.orientation.z = float(raw_data[5]) + msg.pose.orientation.w = float(raw_data[6]) + return msg + +def register(connector): + """将标准 Handler 挂载到 connector""" + connector.register_handler( + "sensor_msgs.msg.JointState", + decode_fn=decode_joint_state, + encode_fn=encode_joint_state + ) + connector.register_handler( + "geometry_msgs.msg.PoseStamped", + decode_fn=decode_pose_stamped, + encode_fn=encode_pose_stamped + ) \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/src/utils/__init__.py b/robodriver/robots/Universal_Client-master/src/utils/__init__.py new file mode 100644 index 0000000..e69de29 diff --git a/robodriver/robots/Universal_Client-master/src/utils/config_loader.py b/robodriver/robots/Universal_Client-master/src/utils/config_loader.py new file mode 100644 index 0000000..d1f562c --- /dev/null +++ b/robodriver/robots/Universal_Client-master/src/utils/config_loader.py @@ -0,0 +1,40 @@ +import yaml +import os + +class ConfigLoader: + def __init__(self, config_relative_path="config/settings.yaml"): + """ + 初始化配置加载器 + :param config_relative_path: 配置文件相对于项目根目录的路径 + """ + self.config_path = config_relative_path + self.data = None + + def load(self): + """ + 执行加载动作,解析 YAML 并返回字典 + """ + # 1. 获取项目根目录 (假设此文件在 src/utils/ 下,往上找3层是根目录) + # 如果你的目录结构变了,这里可能需要调整层级 + base_dir = os.path.dirname(os.path.dirname(os.path.dirname(os.path.abspath(__file__)))) + + # 2. 拼接完整路径 + full_path = os.path.join(base_dir, self.config_path) + + # 3. 检查文件是否存在 + if not os.path.exists(full_path): + raise FileNotFoundError(f"Config file not found at: {full_path}") + + # 4. 读取并解析 + with open(full_path, 'r', encoding='utf-8') as f: + self.data = yaml.safe_load(f) + return self.data + + def get(self, key, default=None): + """ + 可选:封装一个安全的获取方法,防止 KeyError + 用法: loader.get('app') + """ + if self.data is None: + self.load() + return self.data.get(key, default) \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/tests/mock_ros1_publisher.py b/robodriver/robots/Universal_Client-master/tests/mock_ros1_publisher.py new file mode 100644 index 0000000..ee4a641 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/tests/mock_ros1_publisher.py @@ -0,0 +1,112 @@ +#!/usr/bin/env python3 +import rospy +import math +from sensor_msgs.msg import JointState, Image +from geometry_msgs.msg import PoseStamped + +class MockHardwareNodeROS1: + def __init__(self): + # 初始化 ROS 1 节点 + rospy.init_node('mock_hardware_node_ros1', anonymous=True) + + # --- 1. 发布者定义 (完全对齐 yaml 中的 sensors 话题) --- + + # 相机 + self.pub_camera = rospy.Publisher('/camera/color/image_raw', Image, queue_size=1) + + # 主臂 (Leader) + self.pub_ld_l_joint = rospy.Publisher('/left_arm_joint_control', JointState, queue_size=10) + self.pub_ld_r_joint = rospy.Publisher('/right_arm_joint_control', JointState, queue_size=10) + self.pub_ld_l_hand = rospy.Publisher('/cb_left_hand_raw_data', JointState, queue_size=10) + self.pub_ld_r_hand = rospy.Publisher('/cb_right_hand_raw_data', JointState, queue_size=10) + + # 从臂 (Follower) + self.pub_fw_l_joint = rospy.Publisher('/robot1/left_arm/joint_states', JointState, queue_size=10) + self.pub_fw_l_pose = rospy.Publisher('/robot1/left_arm/pose_states', PoseStamped, queue_size=10) + self.pub_fw_r_joint = rospy.Publisher('/robot1/right_arm/joint_states', JointState, queue_size=10) + self.pub_fw_r_pose = rospy.Publisher('/robot1/right_arm/pose_states', PoseStamped, queue_size=10) # 保持 right_armxi 拼写 + + # 灵巧手 (Follower) + self.pub_fw_l_hand = rospy.Publisher('/cb_left_hand_state', JointState, queue_size=10) + self.pub_fw_r_hand = rospy.Publisher('/cb_right_hand_state', JointState, queue_size=10) + + self.step = 0.0 + rospy.loginfo("🚀 ROS 1 Mock Hardware Node started. Mocking all sensor topics at 30Hz...") + + def run(self): + # 按照 yaml 中的 30 fps 进行模拟 + rate = rospy.Rate(30) + + while not rospy.is_shutdown(): + self.step += 0.05 + now = rospy.Time.now() + + # --- A. 模拟主臂数据 (Leader) --- + msg = JointState(); msg.header.stamp = now + msg.position = [math.sin(self.step) * 0.5] * 7 + self.pub_ld_l_joint.publish(msg) + + msg = JointState(); msg.header.stamp = now + msg.position = [math.cos(self.step) * 0.5] * 7 + self.pub_ld_r_joint.publish(msg) + + msg = JointState(); msg.header.stamp = now + msg.position = [abs(math.sin(self.step))] * 10 + self.pub_ld_l_hand.publish(msg) + + msg = JointState(); msg.header.stamp = now + msg.position = [abs(math.cos(self.step))] * 10 + self.pub_ld_r_hand.publish(msg) + + # --- B. 模拟从臂关节数据 (Follower Joints) --- + s_l_joint = JointState(); s_l_joint.header.stamp = now + s_l_joint.name = [f"L{i}_joint" for i in range(1, 8)] + s_l_joint.position = [math.cos(self.step + i) for i in range(7)] + self.pub_fw_l_joint.publish(s_l_joint) + + s_r_joint = JointState(); s_r_joint.header.stamp = now + s_r_joint.name = [f"R{i}_joint" for i in range(1, 8)] + s_r_joint.position = [math.sin(self.step + i) for i in range(7)] + self.pub_fw_r_joint.publish(s_r_joint) + + # --- C. 模拟末端位姿数据 (Follower Poses) --- + def create_mock_pose(offset): + p = PoseStamped(); p.header.stamp = now; p.header.frame_id = "base_link" + p.pose.position.x = 0.5 + 0.1 * math.sin(self.step + offset) + p.pose.position.y = offset + 0.1 * math.cos(self.step) + p.pose.position.z = 0.3 + p.pose.orientation.w = 1.0 + return p + + self.pub_fw_l_pose.publish(create_mock_pose(-0.2)) + self.pub_fw_r_pose.publish(create_mock_pose(0.2)) + + # --- D. 模拟灵巧手 (Follower Hands) --- + msg = JointState(); msg.header.stamp = now + msg.position = [abs(math.sin(self.step))] * 10 + self.pub_fw_l_hand.publish(msg) + + msg = JointState(); msg.header.stamp = now + msg.position = [abs(math.cos(self.step))] * 10 + self.pub_fw_r_hand.publish(msg) + + # --- E. 模拟图像 (Camera) --- + msg_img = Image(); msg_img.header.stamp = now + msg_img.height, msg_img.width = 480, 640 + msg_img.encoding = 'rgb8' + msg_img.step = 640 * 3 + # 让图像颜色随时间产生绿色的渐变呼吸效果 + green_val = int((math.sin(self.step) + 1) * 127) + msg_img.data = bytes([0, green_val, 0] * (640 * 480)) + self.pub_camera.publish(msg_img) + + rate.sleep() + +if __name__ == '__main__': + try: + node = MockHardwareNodeROS1() + node.run() + except rospy.ROSInterruptException: + pass + except Exception as e: + rospy.logerr(f"Error running mock node: {e}") \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/tests/mock_ros2_publisher.py b/robodriver/robots/Universal_Client-master/tests/mock_ros2_publisher.py new file mode 100644 index 0000000..9edd39d --- /dev/null +++ b/robodriver/robots/Universal_Client-master/tests/mock_ros2_publisher.py @@ -0,0 +1,115 @@ +#!/usr/bin/env python3 +import rclpy +from rclpy.node import Node +from sensor_msgs.msg import JointState, Image +from geometry_msgs.msg import PoseStamped +import math + +class MockHardwareNode(Node): + def __init__(self): + super().__init__('mock_hardware_node') + + # --- 1. 发布者定义 --- + # 主臂控制 (Master Control) + self.pub_master_left = self.create_publisher(JointState, '/left_arm_joint_control', 10) + self.pub_master_right = self.create_publisher(JointState, '/right_arm_joint_control', 10) + self.pub_master_left_hand = self.create_publisher(JointState, '/cb_left_hand_raw_data', 10) + self.pub_master_right_hand = self.create_publisher(JointState, '/cb_right_hand_raw_data', 10) + # 从臂状态 (Slave States) + self.pub_l_slave_joint = self.create_publisher(JointState, '/robot1/left_arm/joint_states', 10) + self.pub_l_slave_pose = self.create_publisher(PoseStamped, '/robot1/left_arm/pose_states', 10) + self.pub_r_slave_joint = self.create_publisher(JointState, '/robot1/right_arm/joint_states', 10) + self.pub_r_slave_pose = self.create_publisher(PoseStamped, '/robot1/right_arm/pose_states', 10) + + # 灵巧手 (Hand) + self.pub_hand_right = self.create_publisher(JointState, '/cb_right_hand_state', 10) + self.pub_hand_left = self.create_publisher(JointState, '/cb_left_hand_state', 10) + # 相机 (Camera) + self.pub_camera = self.create_publisher(Image, '/camera/color/image_raw', 10) + + # 定时器 + self.timer = self.create_timer(1.0 / 30.0, self.timer_callback) + self.step = 0.0 + self.get_logger().info("🚀 All systems GO! Mocking all topics...") + + def timer_callback(self): + now = self.get_clock().now().to_msg() + self.step += 0.05 + + # --- A. 模拟主臂控制数据 (Master Arms) --- + m_l_ctrl = JointState() + m_l_ctrl.header.stamp = now + m_l_ctrl.position = [math.sin(self.step) * 0.5] * 7 + self.pub_master_left.publish(m_l_ctrl) + + m_r_ctrl = JointState() + m_r_ctrl.header.stamp = now + m_r_ctrl.position = [math.cos(self.step) * 0.5] * 7 + self.pub_master_right.publish(m_r_ctrl) + + # --- B. 模拟从臂关节数据 (Slave Joints) --- + # 左臂 + s_l_joint = JointState() + s_l_joint.header.stamp = now + s_l_joint.name = [f"L{i}_joint" for i in range(1, 8)] + s_l_joint.position = [math.cos(self.step + i) for i in range(7)] + self.pub_l_slave_joint.publish(s_l_joint) + + # 右臂 + s_r_joint = JointState() + s_r_joint.header.stamp = now + s_r_joint.name = [f"R{i}_joint" for i in range(1, 8)] + s_r_joint.position = [math.sin(self.step + i) for i in range(7)] + self.pub_r_slave_joint.publish(s_r_joint) + + # --- C. 模拟末端位姿数据 (Slave Poses) --- + # 使用简单的正弦波模拟空间位置变化 + def create_mock_pose(offset): + p = PoseStamped() + p.header.stamp = now + p.header.frame_id = "base_link" + p.pose.position.x = 0.5 + 0.1 * math.sin(self.step + offset) + p.pose.position.y = offset + 0.1 * math.cos(self.step) + p.pose.position.z = 0.3 + p.pose.orientation.w = 1.0 # 保持姿态固定 + return p + + self.pub_l_slave_pose.publish(create_mock_pose(-0.2)) # 左手偏左 + self.pub_r_slave_pose.publish(create_mock_pose(0.2)) # 右手偏右 + + # --- D. 模拟灵巧手 (Hand) --- + msg_hand_l = JointState() + msg_hand_l.header.stamp = now + msg_hand_l.name = [f"left_finger_{i}" for i in range(10)] + msg_hand_l.position = [abs(math.sin(self.step))] * 10 + self.pub_hand_left.publish(msg_hand_l) + + msg_hand_r = JointState() + msg_hand_r.header.stamp = now + msg_hand_r.name = [f"right_finger_{i}" for i in range(10)] + msg_hand_r.position = [abs(math.cos(self.step))] * 10 # 使用 cos 让动作交替 + self.pub_hand_right.publish(msg_hand_r) + # --- E. 模拟图像 (Camera) --- + msg_img = Image() + msg_img.header.stamp = now + msg_img.height, msg_img.width = 480, 640 + msg_img.encoding = 'rgb8' + msg_img.step = 640 * 3 + # 这里的图像会随时间变色(从纯黑到纯绿循环) + green_val = int((math.sin(self.step) + 1) * 127) + msg_img.data = bytes([0, green_val, 0] * (640 * 480)) + self.pub_camera.publish(msg_img) + +def main(args=None): + rclpy.init(args=args) + node = MockHardwareNode() + try: + rclpy.spin(node) + except KeyboardInterrupt: + pass + finally: + node.destroy_node() + rclpy.shutdown() + +if __name__ == '__main__': + main() \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/tests/test.py b/robodriver/robots/Universal_Client-master/tests/test.py new file mode 100644 index 0000000..6f67efb --- /dev/null +++ b/robodriver/robots/Universal_Client-master/tests/test.py @@ -0,0 +1,49 @@ +import os +import pytest +from src.utils.config_loader import ConfigLoader +from src.core.factory import create_connector + +def test_config_loader(): + """测试配置加载器是否能正确读取 YAML""" + # 确保配置文件存在 + assert os.path.exists("config/settings.yaml"), "配置文件丢失" + + loader = ConfigLoader("config/settings.yaml") + data = loader.load() + + # 验证关键配置项 + assert "app" in data + assert data["app"]["name"] == "LinkerBot-ZMQ-Hub" + assert data["app"]["middleware"] in ["ros1", "ros2"] + + assert "zmq" in data + assert "pub_address" in data["zmq"] + + assert "devices" in data + assert "leader_left_joints" in data["devices"] + +def test_config_loader_file_not_found(): + """测试读取不存在的文件是否抛出异常""" + loader = ConfigLoader("config/fake_settings.yaml") + with pytest.raises(FileNotFoundError): + loader.load() + +# 由于 GitHub CI 上没有安装 ROS 环境,直接 create_connector 会报错找不到 rclpy/rospy +# 我们可以在这里测试一些纯 Python 的类,比如 ZmqHub 的初始化 +def test_zmq_hub_init(): + """测试 ZMQ Hub 是否能正常初始化 (纯 Python)""" + from src.core.zmq_hub import ZmqHub + mock_config = { + "zmq": { + "pub_address": "tcp://127.0.0.1:15555", + "sub_address": "tcp://127.0.0.1:15556", + "debug": False + } + } + hub = ZmqHub(mock_config) + assert hub.pub_address == "tcp://127.0.0.1:15555" + assert hub.running is False + + # 验证方法存在 + assert hasattr(hub, "publish") + assert hasattr(hub, "publish_image") \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/tests/test_camera.py b/robodriver/robots/Universal_Client-master/tests/test_camera.py new file mode 100644 index 0000000..3def52c --- /dev/null +++ b/robodriver/robots/Universal_Client-master/tests/test_camera.py @@ -0,0 +1,52 @@ +#!/usr/bin/env python3 +import cv2 +print(111) +from pyorbbecsdk import ObCamera + +def main(): + camera = None # 先初始化相机变量,避免未定义报错 + try: + # 1. 创建相机实例(包含在大的try块中,覆盖所有相机操作) + print("1") + camera = ObCamera() + if camera is None: + print("Failed to create ObCamera instance!") + return + + # 2. 打开相机 + if not camera.open(): + print("Failed to open camera!") + return + + print("Camera opened successfully! Press 'q' to quit.") + + # 3. 循环获取帧,添加退出条件和帧处理 + while True: + # 获取帧并判断有效性 + frame = camera.get_frame() + if frame is None or frame.empty(): # 判断帧是否有效(根据pyorbbecsdk实际情况调整) + print("Failed to get valid frame, skipping...") + continue # 跳过无效帧,避免卡死 + + # 显示帧(OpenCV窗口显示,必须步骤) + cv2.imshow("Gemini355 Camera Frame", frame) + + # 监听键盘事件:按'q'退出循环(关键:解决无限死循环) + # waitKey(1) 阻塞1毫秒,监听键盘输入,返回值为ASCII码 + key = cv2.waitKey(1) & 0xFF + if key == ord('q'): + print("Quit command received, exiting...") + break # 退出while循环 + + except Exception as e: # 正确拼写:except + print(f"Error occurred: {e}") + finally: + # 确保相机正常关闭,窗口正常销毁 + if camera is not None: + camera.close() + print("Camera closed successfully!") + cv2.destroyAllWindows() + print("All OpenCV windows destroyed!") + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/tests/test_robot.py b/robodriver/robots/Universal_Client-master/tests/test_robot.py new file mode 100644 index 0000000..734304e --- /dev/null +++ b/robodriver/robots/Universal_Client-master/tests/test_robot.py @@ -0,0 +1,109 @@ +import sys +import os +import time +import math + +sys.path.append(os.getcwd()) +from src.core.factory import create_connector + +def print_group_state(robot, device_key, label): + data = robot.get_state(device_key) + if data: + pos = data.get('position', []) + formatted_pos = [round(x, 3) for x in pos[:6]] + print(f" {label} ({len(pos)}轴): {formatted_pos}{'...' if len(pos)>6 else ''}") + return pos + else: + print(f" ⚠️ {label} 数据尚未就绪") + return None + +def main(): + print("="*50) + print(" LinkerBot 硬件接口测试 (HAL 架构)") + print("="*50) + + try: + robot = create_connector("config/settings.yaml") + robot.start() + print("✅ Robot Connector 初始化并启动成功") + print("⏳ 等待接收传感器数据 (2秒)...") + time.sleep(2) + except Exception as e: + print(f"❌ 初始化失败: {e}") + return + + try: + # ========================================== + # 测试阶段 1: 读取状态 + # ========================================== + print("\n[阶段 1/2] 测试状态读取...") + for i in range(2): + print(f"循环 {i+1}:") + print_group_state(robot, "leader_left_joints", "左主臂") + print_group_state(robot, "follower_left_joints", "左从臂关节") + print_group_state(robot, "follower_left_hand", "左灵巧手") + + pose_data = robot.get_state("follower_left_pose") + if pose_data: + pos = pose_data['position'] + print(f" 左从臂位姿: x={pos['x']:.2f}, y={pos['y']:.2f}, z={pos['z']:.2f}") + + time.sleep(0.5) + + # ========================================== + # 测试阶段 2: 增量式安全控制下发 + # ========================================== + print("\n[阶段 2/2] 测试控制下发 (增量安全测试)...") + input("👉 按回车键开始下发安全增量指令...") + + # --- 1. 机械臂增量控制 --- + print("\n--- 测试机械臂控制 ---") + current_arm_state = robot.get_state("follower_left_joints") + + if current_arm_state and 'position' in current_arm_state: + current_pos = current_arm_state['position'] + # 安全增量:每个关节只增加 0.05 弧度 + safe_target = [pos + 0.05 for pos in current_pos] + + print(f" 当前关节角度: {[round(x, 3) for x in current_pos[:6]]}...") + print(f" 目标安全角度: {[round(x, 3) for x in safe_target[:6]]}...") + + command_data = {"position": safe_target, "follow": True} + success = robot.send_control("follower_left_arm_control", command_data) + if success: + print(" ✅ 机械臂控制指令已下发") + else: + print(" ❌ 机械臂控制指令发送失败") + else: + print(" ⚠️ 无法获取机械臂当前状态,跳过控制测试以确保硬件安全") + + + # --- 2. 灵巧手增量控制 --- + print("\n--- 测试灵巧手控制 ---") + current_hand_state = robot.get_state("follower_left_hand") + + if current_hand_state and 'position' in current_hand_state: + current_hand_pos = current_hand_state['position'] + # 安全增量:手指轻微变化 0.05 + safe_hand_target = [pos + 0.05 for pos in current_hand_pos] + + print(f" 当前手指位置: {[round(x, 3) for x in current_hand_pos[:6]]}...") + print(f" 目标手指位置: {[round(x, 3) for x in safe_hand_target[:6]]}...") + + hand_command_data = {"position": safe_hand_target} + success = robot.send_control("follower_left_hand_control", hand_command_data) + if success: + print(" ✅ 灵巧手控制指令已下发") + else: + print(" ❌ 灵巧手控制指令发送失败") + else: + print(" ⚠️ 无法获取灵巧手当前状态,跳过控制测试以确保硬件安全") + + except KeyboardInterrupt: + print("\n🛑 测试被用户中断") + finally: + robot.stop() + print("\n✅ 底层资源已安全释放") + +if __name__ == "__main__": + main() \ No newline at end of file diff --git a/robodriver/robots/Universal_Client-master/uv.lock b/robodriver/robots/Universal_Client-master/uv.lock new file mode 100644 index 0000000..ddfd0f5 --- /dev/null +++ b/robodriver/robots/Universal_Client-master/uv.lock @@ -0,0 +1,740 @@ +version = 1 +revision = 2 +requires-python = "==3.10.*" +resolution-markers = [ + "sys_platform == 'darwin'", + "platform_machine == 'aarch64' and sys_platform == 'linux'", + "(platform_machine != 'aarch64' and sys_platform == 'linux') or (sys_platform != 'darwin' and sys_platform != 'linux')", +] + +[[package]] +name = "catkin-pkg" +version = "1.1.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "docutils" }, + { name = "packaging" }, + { name = "pyparsing" }, + { name = "python-dateutil" }, + { name = "setuptools" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/1c/7a/dcd7ba56dc82d88b3059a6770828388fc2e136ca4c5d79003f9febf33087/catkin_pkg-1.1.0.tar.gz", hash = "sha256:df1cb6879a3a772e770a100a6613ce8fc508b4855e5b2790106ddad4a8beb43c", size = 65547, upload-time = "2025-09-10T17:34:36.911Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/99/1b/50316bd6f95c50686b35799abebb6168d90ee18b7c03e3065f587f010f7c/catkin_pkg-1.1.0-py3-none-any.whl", hash = "sha256:7f5486b4f5681b5f043316ce10fc638c8d0ba8127146e797c85f4024e4356027", size = 76369, upload-time = "2025-09-10T17:34:35.639Z" }, +] + +[[package]] +name = "certifi" +version = "2025.11.12" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/a2/8c/58f469717fa48465e4a50c014a0400602d3c437d7c0c468e17ada824da3a/certifi-2025.11.12.tar.gz", hash = "sha256:d8ab5478f2ecd78af242878415affce761ca6bc54a22a27e026d7c25357c3316", size = 160538, upload-time = "2025-11-12T02:54:51.517Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/70/7d/9bc192684cea499815ff478dfcdc13835ddf401365057044fb721ec6bddb/certifi-2025.11.12-py3-none-any.whl", hash = "sha256:97de8790030bbd5c2d96b7ec782fc2f7820ef8dba6db909ccf95449f2d062d4b", size = 159438, upload-time = "2025-11-12T02:54:49.735Z" }, +] + +[[package]] +name = "cffi" +version = "2.0.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "pycparser", marker = "implementation_name != 'PyPy'" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/eb/56/b1ba7935a17738ae8453301356628e8147c79dbb825bcbc73dc7401f9846/cffi-2.0.0.tar.gz", hash = "sha256:44d1b5909021139fe36001ae048dbdde8214afa20200eda0f64c068cac5d5529", size = 523588, upload-time = "2025-09-08T23:24:04.541Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/93/d7/516d984057745a6cd96575eea814fe1edd6646ee6efd552fb7b0921dec83/cffi-2.0.0-cp310-cp310-macosx_10_13_x86_64.whl", hash = "sha256:0cf2d91ecc3fcc0625c2c530fe004f82c110405f101548512cce44322fa8ac44", size = 184283, upload-time = "2025-09-08T23:22:08.01Z" }, + { url = "https://files.pythonhosted.org/packages/9e/84/ad6a0b408daa859246f57c03efd28e5dd1b33c21737c2db84cae8c237aa5/cffi-2.0.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:f73b96c41e3b2adedc34a7356e64c8eb96e03a3782b535e043a986276ce12a49", size = 180504, upload-time = "2025-09-08T23:22:10.637Z" }, + { url = "https://files.pythonhosted.org/packages/50/bd/b1a6362b80628111e6653c961f987faa55262b4002fcec42308cad1db680/cffi-2.0.0-cp310-cp310-manylinux1_i686.manylinux2014_i686.manylinux_2_17_i686.manylinux_2_5_i686.whl", hash = "sha256:53f77cbe57044e88bbd5ed26ac1d0514d2acf0591dd6bb02a3ae37f76811b80c", size = 208811, upload-time = "2025-09-08T23:22:12.267Z" }, + { url = "https://files.pythonhosted.org/packages/4f/27/6933a8b2562d7bd1fb595074cf99cc81fc3789f6a6c05cdabb46284a3188/cffi-2.0.0-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:3e837e369566884707ddaf85fc1744b47575005c0a229de3327f8f9a20f4efeb", size = 216402, upload-time = "2025-09-08T23:22:13.455Z" }, + { url = "https://files.pythonhosted.org/packages/05/eb/b86f2a2645b62adcfff53b0dd97e8dfafb5c8aa864bd0d9a2c2049a0d551/cffi-2.0.0-cp310-cp310-manylinux2014_ppc64le.manylinux_2_17_ppc64le.whl", hash = "sha256:5eda85d6d1879e692d546a078b44251cdd08dd1cfb98dfb77b670c97cee49ea0", size = 203217, upload-time = "2025-09-08T23:22:14.596Z" }, + { url = "https://files.pythonhosted.org/packages/9f/e0/6cbe77a53acf5acc7c08cc186c9928864bd7c005f9efd0d126884858a5fe/cffi-2.0.0-cp310-cp310-manylinux2014_s390x.manylinux_2_17_s390x.whl", hash = "sha256:9332088d75dc3241c702d852d4671613136d90fa6881da7d770a483fd05248b4", size = 203079, upload-time = "2025-09-08T23:22:15.769Z" }, + { url = "https://files.pythonhosted.org/packages/98/29/9b366e70e243eb3d14a5cb488dfd3a0b6b2f1fb001a203f653b93ccfac88/cffi-2.0.0-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:fc7de24befaeae77ba923797c7c87834c73648a05a4bde34b3b7e5588973a453", size = 216475, upload-time = "2025-09-08T23:22:17.427Z" }, + { url = "https://files.pythonhosted.org/packages/21/7a/13b24e70d2f90a322f2900c5d8e1f14fa7e2a6b3332b7309ba7b2ba51a5a/cffi-2.0.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:cf364028c016c03078a23b503f02058f1814320a56ad535686f90565636a9495", size = 218829, upload-time = "2025-09-08T23:22:19.069Z" }, + { url = "https://files.pythonhosted.org/packages/60/99/c9dc110974c59cc981b1f5b66e1d8af8af764e00f0293266824d9c4254bc/cffi-2.0.0-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:e11e82b744887154b182fd3e7e8512418446501191994dbf9c9fc1f32cc8efd5", size = 211211, upload-time = "2025-09-08T23:22:20.588Z" }, + { url = "https://files.pythonhosted.org/packages/49/72/ff2d12dbf21aca1b32a40ed792ee6b40f6dc3a9cf1644bd7ef6e95e0ac5e/cffi-2.0.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:8ea985900c5c95ce9db1745f7933eeef5d314f0565b27625d9a10ec9881e1bfb", size = 218036, upload-time = "2025-09-08T23:22:22.143Z" }, + { url = "https://files.pythonhosted.org/packages/e2/cc/027d7fb82e58c48ea717149b03bcadcbdc293553edb283af792bd4bcbb3f/cffi-2.0.0-cp310-cp310-win32.whl", hash = "sha256:1f72fb8906754ac8a2cc3f9f5aaa298070652a0ffae577e0ea9bd480dc3c931a", size = 172184, upload-time = "2025-09-08T23:22:23.328Z" }, + { url = "https://files.pythonhosted.org/packages/33/fa/072dd15ae27fbb4e06b437eb6e944e75b068deb09e2a2826039e49ee2045/cffi-2.0.0-cp310-cp310-win_amd64.whl", hash = "sha256:b18a3ed7d5b3bd8d9ef7a8cb226502c6bf8308df1525e1cc676c3680e7176739", size = 182790, upload-time = "2025-09-08T23:22:24.752Z" }, +] + +[[package]] +name = "charset-normalizer" +version = "3.4.4" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/13/69/33ddede1939fdd074bce5434295f38fae7136463422fe4fd3e0e89b98062/charset_normalizer-3.4.4.tar.gz", hash = "sha256:94537985111c35f28720e43603b8e7b43a6ecfb2ce1d3058bbe955b73404e21a", size = 129418, upload-time = "2025-10-14T04:42:32.879Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/1f/b8/6d51fc1d52cbd52cd4ccedd5b5b2f0f6a11bbf6765c782298b0f3e808541/charset_normalizer-3.4.4-cp310-cp310-macosx_10_9_universal2.whl", hash = "sha256:e824f1492727fa856dd6eda4f7cee25f8518a12f3c4a56a74e8095695089cf6d", size = 209709, upload-time = "2025-10-14T04:40:11.385Z" }, + { url = "https://files.pythonhosted.org/packages/5c/af/1f9d7f7faafe2ddfb6f72a2e07a548a629c61ad510fe60f9630309908fef/charset_normalizer-3.4.4-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:4bd5d4137d500351a30687c2d3971758aac9a19208fc110ccb9d7188fbe709e8", size = 148814, upload-time = "2025-10-14T04:40:13.135Z" }, + { url = "https://files.pythonhosted.org/packages/79/3d/f2e3ac2bbc056ca0c204298ea4e3d9db9b4afe437812638759db2c976b5f/charset_normalizer-3.4.4-cp310-cp310-manylinux2014_armv7l.manylinux_2_17_armv7l.manylinux_2_31_armv7l.whl", hash = "sha256:027f6de494925c0ab2a55eab46ae5129951638a49a34d87f4c3eda90f696b4ad", size = 144467, upload-time = "2025-10-14T04:40:14.728Z" }, + { url = "https://files.pythonhosted.org/packages/ec/85/1bf997003815e60d57de7bd972c57dc6950446a3e4ccac43bc3070721856/charset_normalizer-3.4.4-cp310-cp310-manylinux2014_ppc64le.manylinux_2_17_ppc64le.manylinux_2_28_ppc64le.whl", hash = "sha256:f820802628d2694cb7e56db99213f930856014862f3fd943d290ea8438d07ca8", size = 162280, upload-time = "2025-10-14T04:40:16.14Z" }, + { url = "https://files.pythonhosted.org/packages/3e/8e/6aa1952f56b192f54921c436b87f2aaf7c7a7c3d0d1a765547d64fd83c13/charset_normalizer-3.4.4-cp310-cp310-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:798d75d81754988d2565bff1b97ba5a44411867c0cf32b77a7e8f8d84796b10d", size = 159454, upload-time = "2025-10-14T04:40:17.567Z" }, + { url = "https://files.pythonhosted.org/packages/36/3b/60cbd1f8e93aa25d1c669c649b7a655b0b5fb4c571858910ea9332678558/charset_normalizer-3.4.4-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9d1bb833febdff5c8927f922386db610b49db6e0d4f4ee29601d71e7c2694313", size = 153609, upload-time = "2025-10-14T04:40:19.08Z" }, + { url = "https://files.pythonhosted.org/packages/64/91/6a13396948b8fd3c4b4fd5bc74d045f5637d78c9675585e8e9fbe5636554/charset_normalizer-3.4.4-cp310-cp310-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:9cd98cdc06614a2f768d2b7286d66805f94c48cde050acdbbb7db2600ab3197e", size = 151849, upload-time = "2025-10-14T04:40:20.607Z" }, + { url = "https://files.pythonhosted.org/packages/b7/7a/59482e28b9981d105691e968c544cc0df3b7d6133152fb3dcdc8f135da7a/charset_normalizer-3.4.4-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:077fbb858e903c73f6c9db43374fd213b0b6a778106bc7032446a8e8b5b38b93", size = 151586, upload-time = "2025-10-14T04:40:21.719Z" }, + { url = "https://files.pythonhosted.org/packages/92/59/f64ef6a1c4bdd2baf892b04cd78792ed8684fbc48d4c2afe467d96b4df57/charset_normalizer-3.4.4-cp310-cp310-musllinux_1_2_armv7l.whl", hash = "sha256:244bfb999c71b35de57821b8ea746b24e863398194a4014e4c76adc2bbdfeff0", size = 145290, upload-time = "2025-10-14T04:40:23.069Z" }, + { url = "https://files.pythonhosted.org/packages/6b/63/3bf9f279ddfa641ffa1962b0db6a57a9c294361cc2f5fcac997049a00e9c/charset_normalizer-3.4.4-cp310-cp310-musllinux_1_2_ppc64le.whl", hash = "sha256:64b55f9dce520635f018f907ff1b0df1fdc31f2795a922fb49dd14fbcdf48c84", size = 163663, upload-time = "2025-10-14T04:40:24.17Z" }, + { url = "https://files.pythonhosted.org/packages/ed/09/c9e38fc8fa9e0849b172b581fd9803bdf6e694041127933934184e19f8c3/charset_normalizer-3.4.4-cp310-cp310-musllinux_1_2_riscv64.whl", hash = "sha256:faa3a41b2b66b6e50f84ae4a68c64fcd0c44355741c6374813a800cd6695db9e", size = 151964, upload-time = "2025-10-14T04:40:25.368Z" }, + { url = "https://files.pythonhosted.org/packages/d2/d1/d28b747e512d0da79d8b6a1ac18b7ab2ecfd81b2944c4c710e166d8dd09c/charset_normalizer-3.4.4-cp310-cp310-musllinux_1_2_s390x.whl", hash = "sha256:6515f3182dbe4ea06ced2d9e8666d97b46ef4c75e326b79bb624110f122551db", size = 161064, upload-time = "2025-10-14T04:40:26.806Z" }, + { url = "https://files.pythonhosted.org/packages/bb/9a/31d62b611d901c3b9e5500c36aab0ff5eb442043fb3a1c254200d3d397d9/charset_normalizer-3.4.4-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:cc00f04ed596e9dc0da42ed17ac5e596c6ccba999ba6bd92b0e0aef2f170f2d6", size = 155015, upload-time = "2025-10-14T04:40:28.284Z" }, + { url = "https://files.pythonhosted.org/packages/1f/f3/107e008fa2bff0c8b9319584174418e5e5285fef32f79d8ee6a430d0039c/charset_normalizer-3.4.4-cp310-cp310-win32.whl", hash = "sha256:f34be2938726fc13801220747472850852fe6b1ea75869a048d6f896838c896f", size = 99792, upload-time = "2025-10-14T04:40:29.613Z" }, + { url = "https://files.pythonhosted.org/packages/eb/66/e396e8a408843337d7315bab30dbf106c38966f1819f123257f5520f8a96/charset_normalizer-3.4.4-cp310-cp310-win_amd64.whl", hash = "sha256:a61900df84c667873b292c3de315a786dd8dac506704dea57bc957bd31e22c7d", size = 107198, upload-time = "2025-10-14T04:40:30.644Z" }, + { url = "https://files.pythonhosted.org/packages/b5/58/01b4f815bf0312704c267f2ccb6e5d42bcc7752340cd487bc9f8c3710597/charset_normalizer-3.4.4-cp310-cp310-win_arm64.whl", hash = "sha256:cead0978fc57397645f12578bfd2d5ea9138ea0fac82b2f63f7f7c6877986a69", size = 100262, upload-time = "2025-10-14T04:40:32.108Z" }, + { url = "https://files.pythonhosted.org/packages/0a/4c/925909008ed5a988ccbb72dcc897407e5d6d3bd72410d69e051fc0c14647/charset_normalizer-3.4.4-py3-none-any.whl", hash = "sha256:7a32c560861a02ff789ad905a2fe94e3f840803362c84fecf1851cb4cf3dc37f", size = 53402, upload-time = "2025-10-14T04:42:31.76Z" }, +] + +[[package]] +name = "colorama" +version = "0.4.6" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/d8/53/6f443c9a4a8358a93a6792e2acffb9d9d5cb0a5cfd8802644b7b1c9a02e4/colorama-0.4.6.tar.gz", hash = "sha256:08695f5cb7ed6e0531a20572697297273c47b8cae5a63ffc6d6ed5c201be6e44", size = 27697, upload-time = "2022-10-25T02:36:22.414Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/d1/d6/3965ed04c63042e047cb6a3e6ed1a63a35087b6a609aa3a15ed8ac56c221/colorama-0.4.6-py2.py3-none-any.whl", hash = "sha256:4f1d9991f5acc0ca119f9d443620b77f9d6b33703e51011c16baf57afb285fc6", size = 25335, upload-time = "2022-10-25T02:36:20.889Z" }, +] + +[[package]] +name = "cuda-bindings" +version = "13.2.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "cuda-pathfinder", marker = "sys_platform != 'darwin'" }, +] +wheels = [ + { url = "https://files.pythonhosted.org/packages/1a/fe/7351d7e586a8b4c9f89731bfe4cf0148223e8f9903ff09571f78b3fb0682/cuda_bindings-13.2.0-cp310-cp310-manylinux_2_24_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:08b395f79cb89ce0cd8effff07c4a1e20101b873c256a1aeb286e8fd7bd0f556", size = 5744254, upload-time = "2026-03-11T00:12:29.798Z" }, + { url = "https://files.pythonhosted.org/packages/aa/ef/184aa775e970fc089942cd9ec6302e6e44679d4c14549c6a7ea45bf7f798/cuda_bindings-13.2.0-cp310-cp310-manylinux_2_24_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:d6f3682ec3c4769326aafc67c2ba669d97d688d0b7e63e659d36d2f8b72f32d6", size = 6329075, upload-time = "2026-03-11T00:12:32.319Z" }, +] + +[[package]] +name = "cuda-pathfinder" +version = "1.5.1" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/c4/74/8c66861b873d8eed51fde56d3091baa4906a56f0d4390cae991f2d41dda5/cuda_pathfinder-1.5.1-py3-none-any.whl", hash = "sha256:b3718097fb57cf9e8a904dd072d806f2c9a27627e35c020b06ab9454bcec08c0", size = 49861, upload-time = "2026-04-03T16:41:22.203Z" }, +] + +[[package]] +name = "cuda-toolkit" +version = "13.0.2" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/57/b2/453099f5f3b698d7d0eab38916aac44c7f76229f451709e2eb9db6615dcd/cuda_toolkit-13.0.2-py2.py3-none-any.whl", hash = "sha256:b198824cf2f54003f50d64ada3a0f184b42ca0846c1c94192fa269ecd97a66eb", size = 2364, upload-time = "2025-12-19T23:24:07.328Z" }, +] + +[package.optional-dependencies] +cublas = [ + { name = "nvidia-cublas", marker = "sys_platform == 'linux' or sys_platform == 'win32'" }, +] +cudart = [ + { name = "nvidia-cuda-runtime", marker = "sys_platform == 'linux' or sys_platform == 'win32'" }, +] +cufft = [ + { name = "nvidia-cufft", marker = "sys_platform == 'linux' or sys_platform == 'win32'" }, +] +cufile = [ + { name = "nvidia-cufile", marker = "sys_platform == 'linux'" }, +] +cupti = [ + { name = "nvidia-cuda-cupti", marker = "sys_platform == 'linux' or sys_platform == 'win32'" }, +] +curand = [ + { name = "nvidia-curand", marker = "sys_platform == 'linux' or sys_platform == 'win32'" }, +] +cusolver = [ + { name = "nvidia-cusolver", marker = "sys_platform == 'linux' or sys_platform == 'win32'" }, +] +cusparse = [ + { name = "nvidia-cusparse", marker = "sys_platform == 'linux' or sys_platform == 'win32'" }, +] +nvjitlink = [ + { name = "nvidia-nvjitlink", marker = "sys_platform == 'linux' or sys_platform == 'win32'" }, +] +nvrtc = [ + { name = "nvidia-cuda-nvrtc", marker = "sys_platform == 'linux' or sys_platform == 'win32'" }, +] +nvtx = [ + { name = "nvidia-nvtx", marker = "sys_platform == 'linux' or sys_platform == 'win32'" }, +] + +[[package]] +name = "distro" +version = "1.9.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/fc/f8/98eea607f65de6527f8a2e8885fc8015d3e6f5775df186e443e0964a11c3/distro-1.9.0.tar.gz", hash = "sha256:2fa77c6fd8940f116ee1d6b94a2f90b13b5ea8d019b98bc8bafdcabcdd9bdbed", size = 60722, upload-time = "2023-12-24T09:54:32.31Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/12/b3/231ffd4ab1fc9d679809f356cebee130ac7daa00d6d6f3206dd4fd137e9e/distro-1.9.0-py3-none-any.whl", hash = "sha256:7bffd925d65168f85027d8da9af6bddab658135b840670a223589bc0c8ef02b2", size = 20277, upload-time = "2023-12-24T09:54:30.421Z" }, +] + +[[package]] +name = "docutils" +version = "0.22.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/d9/02/111134bfeb6e6c7ac4c74594e39a59f6c0195dc4846afbeac3cba60f1927/docutils-0.22.3.tar.gz", hash = "sha256:21486ae730e4ca9f622677b1412b879af1791efcfba517e4c6f60be543fc8cdd", size = 2290153, upload-time = "2025-11-06T02:35:55.655Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/11/a8/c6a4b901d17399c77cd81fb001ce8961e9f5e04d3daf27e8925cb012e163/docutils-0.22.3-py3-none-any.whl", hash = "sha256:bd772e4aca73aff037958d44f2be5229ded4c09927fcf8690c577b66234d6ceb", size = 633032, upload-time = "2025-11-06T02:35:52.391Z" }, +] + +[[package]] +name = "exceptiongroup" +version = "1.3.1" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "typing-extensions" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/50/79/66800aadf48771f6b62f7eb014e352e5d06856655206165d775e675a02c9/exceptiongroup-1.3.1.tar.gz", hash = "sha256:8b412432c6055b0b7d14c310000ae93352ed6754f70fa8f7c34141f91c4e3219", size = 30371, upload-time = "2025-11-21T23:01:54.787Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/8a/0e/97c33bf5009bdbac74fd2beace167cab3f978feb69cc36f1ef79360d6c4e/exceptiongroup-1.3.1-py3-none-any.whl", hash = "sha256:a7a39a3bd276781e98394987d3a5701d0c4edffb633bb7a5144577f82c773598", size = 16740, upload-time = "2025-11-21T23:01:53.443Z" }, +] + +[[package]] +name = "filelock" +version = "3.25.2" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/94/b8/00651a0f559862f3bb7d6f7477b192afe3f583cc5e26403b44e59a55ab34/filelock-3.25.2.tar.gz", hash = "sha256:b64ece2b38f4ca29dd3e810287aa8c48182bbecd1ae6e9ae126c9b35f1382694", size = 40480, upload-time = "2026-03-11T20:45:38.487Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/a4/a5/842ae8f0c08b61d6484b52f99a03510a3a72d23141942d216ebe81fefbce/filelock-3.25.2-py3-none-any.whl", hash = "sha256:ca8afb0da15f229774c9ad1b455ed96e85a81373065fb10446672f64444ddf70", size = 26759, upload-time = "2026-03-11T20:45:37.437Z" }, +] + +[[package]] +name = "fsspec" +version = "2026.3.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/e1/cf/b50ddf667c15276a9ab15a70ef5f257564de271957933ffea49d2cdbcdfb/fsspec-2026.3.0.tar.gz", hash = "sha256:1ee6a0e28677557f8c2f994e3eea77db6392b4de9cd1f5d7a9e87a0ae9d01b41", size = 313547, upload-time = "2026-03-27T19:11:14.892Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/d5/1f/5f4a3cd9e4440e9d9bc78ad0a91a1c8d46b4d429d5239ebe6793c9fe5c41/fsspec-2026.3.0-py3-none-any.whl", hash = "sha256:d2ceafaad1b3457968ed14efa28798162f1638dbb5d2a6868a2db002a5ee39a4", size = 202595, upload-time = "2026-03-27T19:11:13.595Z" }, +] + +[[package]] +name = "idna" +version = "3.11" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/6f/6d/0703ccc57f3a7233505399edb88de3cbd678da106337b9fcde432b65ed60/idna-3.11.tar.gz", hash = "sha256:795dafcc9c04ed0c1fb032c2aa73654d8e8c5023a7df64a53f39190ada629902", size = 194582, upload-time = "2025-10-12T14:55:20.501Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/0e/61/66938bbb5fc52dbdf84594873d5b51fb1f7c7794e9c0f5bd885f30bc507b/idna-3.11-py3-none-any.whl", hash = "sha256:771a87f49d9defaf64091e6e6fe9c18d4833f140bd19464795bc32d966ca37ea", size = 71008, upload-time = "2025-10-12T14:55:18.883Z" }, +] + +[[package]] +name = "iniconfig" +version = "2.3.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/72/34/14ca021ce8e5dfedc35312d08ba8bf51fdd999c576889fc2c24cb97f4f10/iniconfig-2.3.0.tar.gz", hash = "sha256:c76315c77db068650d49c5b56314774a7804df16fee4402c1f19d6d15d8c4730", size = 20503, upload-time = "2025-10-18T21:55:43.219Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/cb/b1/3846dd7f199d53cb17f49cba7e651e9ce294d8497c8c150530ed11865bb8/iniconfig-2.3.0-py3-none-any.whl", hash = "sha256:f631c04d2c48c52b84d0d0549c99ff3859c98df65b3101406327ecc7d53fbf12", size = 7484, upload-time = "2025-10-18T21:55:41.639Z" }, +] + +[[package]] +name = "jinja2" +version = "3.1.6" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "markupsafe" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/df/bf/f7da0350254c0ed7c72f3e33cef02e048281fec7ecec5f032d4aac52226b/jinja2-3.1.6.tar.gz", hash = "sha256:0137fb05990d35f1275a587e9aee6d56da821fc83491a0fb838183be43f66d6d", size = 245115, upload-time = "2025-03-05T20:05:02.478Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/62/a1/3d680cbfd5f4b8f15abc1d571870c5fc3e594bb582bc3b64ea099db13e56/jinja2-3.1.6-py3-none-any.whl", hash = "sha256:85ece4451f492d0c13c5dd7c13a64681a86afae63a5f347908daf103ce6d2f67", size = 134899, upload-time = "2025-03-05T20:05:00.369Z" }, +] + +[[package]] +name = "markupsafe" +version = "3.0.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/7e/99/7690b6d4034fffd95959cbe0c02de8deb3098cc577c67bb6a24fe5d7caa7/markupsafe-3.0.3.tar.gz", hash = "sha256:722695808f4b6457b320fdc131280796bdceb04ab50fe1795cd540799ebe1698", size = 80313, upload-time = "2025-09-27T18:37:40.426Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/e8/4b/3541d44f3937ba468b75da9eebcae497dcf67adb65caa16760b0a6807ebb/markupsafe-3.0.3-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:2f981d352f04553a7171b8e44369f2af4055f888dfb147d55e42d29e29e74559", size = 11631, upload-time = "2025-09-27T18:36:05.558Z" }, + { url = "https://files.pythonhosted.org/packages/98/1b/fbd8eed11021cabd9226c37342fa6ca4e8a98d8188a8d9b66740494960e4/markupsafe-3.0.3-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:e1c1493fb6e50ab01d20a22826e57520f1284df32f2d8601fdd90b6304601419", size = 12057, upload-time = "2025-09-27T18:36:07.165Z" }, + { url = "https://files.pythonhosted.org/packages/40/01/e560d658dc0bb8ab762670ece35281dec7b6c1b33f5fbc09ebb57a185519/markupsafe-3.0.3-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:1ba88449deb3de88bd40044603fafffb7bc2b055d626a330323a9ed736661695", size = 22050, upload-time = "2025-09-27T18:36:08.005Z" }, + { url = "https://files.pythonhosted.org/packages/af/cd/ce6e848bbf2c32314c9b237839119c5a564a59725b53157c856e90937b7a/markupsafe-3.0.3-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:f42d0984e947b8adf7dd6dde396e720934d12c506ce84eea8476409563607591", size = 20681, upload-time = "2025-09-27T18:36:08.881Z" }, + { url = "https://files.pythonhosted.org/packages/c9/2a/b5c12c809f1c3045c4d580b035a743d12fcde53cf685dbc44660826308da/markupsafe-3.0.3-cp310-cp310-manylinux_2_31_riscv64.manylinux_2_39_riscv64.whl", hash = "sha256:c0c0b3ade1c0b13b936d7970b1d37a57acde9199dc2aecc4c336773e1d86049c", size = 20705, upload-time = "2025-09-27T18:36:10.131Z" }, + { url = "https://files.pythonhosted.org/packages/cf/e3/9427a68c82728d0a88c50f890d0fc072a1484de2f3ac1ad0bfc1a7214fd5/markupsafe-3.0.3-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:0303439a41979d9e74d18ff5e2dd8c43ed6c6001fd40e5bf2e43f7bd9bbc523f", size = 21524, upload-time = "2025-09-27T18:36:11.324Z" }, + { url = "https://files.pythonhosted.org/packages/bc/36/23578f29e9e582a4d0278e009b38081dbe363c5e7165113fad546918a232/markupsafe-3.0.3-cp310-cp310-musllinux_1_2_riscv64.whl", hash = "sha256:d2ee202e79d8ed691ceebae8e0486bd9a2cd4794cec4824e1c99b6f5009502f6", size = 20282, upload-time = "2025-09-27T18:36:12.573Z" }, + { url = "https://files.pythonhosted.org/packages/56/21/dca11354e756ebd03e036bd8ad58d6d7168c80ce1fe5e75218e4945cbab7/markupsafe-3.0.3-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:177b5253b2834fe3678cb4a5f0059808258584c559193998be2601324fdeafb1", size = 20745, upload-time = "2025-09-27T18:36:13.504Z" }, + { url = "https://files.pythonhosted.org/packages/87/99/faba9369a7ad6e4d10b6a5fbf71fa2a188fe4a593b15f0963b73859a1bbd/markupsafe-3.0.3-cp310-cp310-win32.whl", hash = "sha256:2a15a08b17dd94c53a1da0438822d70ebcd13f8c3a95abe3a9ef9f11a94830aa", size = 14571, upload-time = "2025-09-27T18:36:14.779Z" }, + { url = "https://files.pythonhosted.org/packages/d6/25/55dc3ab959917602c96985cb1253efaa4ff42f71194bddeb61eb7278b8be/markupsafe-3.0.3-cp310-cp310-win_amd64.whl", hash = "sha256:c4ffb7ebf07cfe8931028e3e4c85f0357459a3f9f9490886198848f4fa002ec8", size = 15056, upload-time = "2025-09-27T18:36:16.125Z" }, + { url = "https://files.pythonhosted.org/packages/d0/9e/0a02226640c255d1da0b8d12e24ac2aa6734da68bff14c05dd53b94a0fc3/markupsafe-3.0.3-cp310-cp310-win_arm64.whl", hash = "sha256:e2103a929dfa2fcaf9bb4e7c091983a49c9ac3b19c9061b6d5427dd7d14d81a1", size = 13932, upload-time = "2025-09-27T18:36:17.311Z" }, +] + +[[package]] +name = "mpmath" +version = "1.3.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/e0/47/dd32fa426cc72114383ac549964eecb20ecfd886d1e5ccf5340b55b02f57/mpmath-1.3.0.tar.gz", hash = "sha256:7a28eb2a9774d00c7bc92411c19a89209d5da7c4c9a9e227be8330a23a25b91f", size = 508106, upload-time = "2023-03-07T16:47:11.061Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/43/e3/7d92a15f894aa0c9c4b49b8ee9ac9850d6e63b03c9c32c0367a13ae62209/mpmath-1.3.0-py3-none-any.whl", hash = "sha256:a0b2b9fe80bbcd81a6647ff13108738cfb482d481d826cc0e02f5b35e5c88d2c", size = 536198, upload-time = "2023-03-07T16:47:09.197Z" }, +] + +[[package]] +name = "networkx" +version = "3.4.2" +source = { registry = "https://pypi.org/simple" } +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 = [ + { url = "https://files.pythonhosted.org/packages/b9/54/dd730b32ea14ea797530a4479b2ed46a6fb250f682a9cfb997e968bf0261/networkx-3.4.2-py3-none-any.whl", hash = "sha256:df5d4365b724cf81b8c6a7312509d0c22386097011ad1abe274afd5e9d3bbc5f", size = 1723263, upload-time = "2024-10-21T12:39:36.247Z" }, +] + +[[package]] +name = "numpy" +version = "1.24.4" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/a4/9b/027bec52c633f6556dba6b722d9a0befb40498b9ceddd29cbe67a45a127c/numpy-1.24.4.tar.gz", hash = "sha256:80f5e3a4e498641401868df4208b74581206afbee7cf7b8329daae82676d9463", size = 10911229, upload-time = "2023-06-26T13:39:33.218Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/6b/80/6cdfb3e275d95155a34659163b83c09e3a3ff9f1456880bec6cc63d71083/numpy-1.24.4-cp310-cp310-macosx_10_9_x86_64.whl", hash = "sha256:c0bfb52d2169d58c1cdb8cc1f16989101639b34c7d3ce60ed70b19c63eba0b64", size = 19789140, upload-time = "2023-06-26T13:22:33.184Z" }, + { url = "https://files.pythonhosted.org/packages/64/5f/3f01d753e2175cfade1013eea08db99ba1ee4bdb147ebcf3623b75d12aa7/numpy-1.24.4-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:ed094d4f0c177b1b8e7aa9cba7d6ceed51c0e569a5318ac0ca9a090680a6a1b1", size = 13854297, upload-time = "2023-06-26T13:22:59.541Z" }, + { url = "https://files.pythonhosted.org/packages/5a/b3/2f9c21d799fa07053ffa151faccdceeb69beec5a010576b8991f614021f7/numpy-1.24.4-cp310-cp310-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:79fc682a374c4a8ed08b331bef9c5f582585d1048fa6d80bc6c35bc384eee9b4", size = 13995611, upload-time = "2023-06-26T13:23:22.167Z" }, + { url = "https://files.pythonhosted.org/packages/10/be/ae5bf4737cb79ba437879915791f6f26d92583c738d7d960ad94e5c36adf/numpy-1.24.4-cp310-cp310-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:7ffe43c74893dbf38c2b0a1f5428760a1a9c98285553c89e12d70a96a7f3a4d6", size = 17282357, upload-time = "2023-06-26T13:23:51.446Z" }, + { url = "https://files.pythonhosted.org/packages/c0/64/908c1087be6285f40e4b3e79454552a701664a079321cff519d8c7051d06/numpy-1.24.4-cp310-cp310-win32.whl", hash = "sha256:4c21decb6ea94057331e111a5bed9a79d335658c27ce2adb580fb4d54f2ad9bc", size = 12429222, upload-time = "2023-06-26T13:24:13.849Z" }, + { url = "https://files.pythonhosted.org/packages/22/55/3d5a7c1142e0d9329ad27cece17933b0e2ab4e54ddc5c1861fbfeb3f7693/numpy-1.24.4-cp310-cp310-win_amd64.whl", hash = "sha256:b4bea75e47d9586d31e892a7401f76e909712a0fd510f58f5337bea9572c571e", size = 14841514, upload-time = "2023-06-26T13:24:38.129Z" }, +] + +[[package]] +name = "nvidia-cublas" +version = "13.1.0.3" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/e1/a5/fce49e2ae977e0ccc084e5adafceb4f0ac0c8333cb6863501618a7277f67/nvidia_cublas-13.1.0.3-py3-none-manylinux_2_27_aarch64.whl", hash = "sha256:c86fc7f7ae36d7528288c5d88098edcb7b02c633d262e7ddbb86b0ad91be5df2", size = 542851226, upload-time = "2025-10-09T08:59:04.818Z" }, + { url = "https://files.pythonhosted.org/packages/e7/44/423ac00af4dd95a5aeb27207e2c0d9b7118702149bf4704c3ddb55bb7429/nvidia_cublas-13.1.0.3-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:ee8722c1f0145ab246bccb9e452153b5e0515fd094c3678df50b2a0888b8b171", size = 423133236, upload-time = "2025-10-09T08:59:32.536Z" }, +] + +[[package]] +name = "nvidia-cuda-cupti" +version = "13.0.85" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/2a/2a/80353b103fc20ce05ef51e928daed4b6015db4aaa9162ed0997090fe2250/nvidia_cuda_cupti-13.0.85-py3-none-manylinux_2_25_aarch64.whl", hash = "sha256:796bd679890ee55fb14a94629b698b6db54bcfd833d391d5e94017dd9d7d3151", size = 10310827, upload-time = "2025-09-04T08:26:42.012Z" }, + { url = "https://files.pythonhosted.org/packages/33/6d/737d164b4837a9bbd202f5ae3078975f0525a55730fe871d8ed4e3b952b0/nvidia_cuda_cupti-13.0.85-py3-none-manylinux_2_25_x86_64.whl", hash = "sha256:4eb01c08e859bf924d222250d2e8f8b8ff6d3db4721288cf35d14252a4d933c8", size = 10715597, upload-time = "2025-09-04T08:26:51.312Z" }, +] + +[[package]] +name = "nvidia-cuda-nvrtc" +version = "13.0.88" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/c3/68/483a78f5e8f31b08fb1bb671559968c0ca3a065ac7acabfc7cee55214fd6/nvidia_cuda_nvrtc-13.0.88-py3-none-manylinux2010_x86_64.manylinux_2_12_x86_64.whl", hash = "sha256:ad9b6d2ead2435f11cbb6868809d2adeeee302e9bb94bcf0539c7a40d80e8575", size = 90215200, upload-time = "2025-09-04T08:28:44.204Z" }, + { url = "https://files.pythonhosted.org/packages/b7/dc/6bb80850e0b7edd6588d560758f17e0550893a1feaf436807d64d2da040f/nvidia_cuda_nvrtc-13.0.88-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:d27f20a0ca67a4bb34268a5e951033496c5b74870b868bacd046b1b8e0c3267b", size = 43015449, upload-time = "2025-09-04T08:28:20.239Z" }, +] + +[[package]] +name = "nvidia-cuda-runtime" +version = "13.0.96" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/87/4f/17d7b9b8e285199c58ce28e31b5c5bbaa4d8271af06a89b6405258245de2/nvidia_cuda_runtime-13.0.96-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:ef9bcbe90493a2b9d810e43d249adb3d02e98dd30200d86607d8d02687c43f55", size = 2261060, upload-time = "2025-10-09T08:55:15.78Z" }, + { url = "https://files.pythonhosted.org/packages/2e/24/d1558f3b68b1d26e706813b1d10aa1d785e4698c425af8db8edc3dced472/nvidia_cuda_runtime-13.0.96-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:7f82250d7782aa23b6cfe765ecc7db554bd3c2870c43f3d1821f1d18aebf0548", size = 2243632, upload-time = "2025-10-09T08:55:36.117Z" }, +] + +[[package]] +name = "nvidia-cudnn-cu13" +version = "9.19.0.56" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "nvidia-cublas", marker = "sys_platform != 'darwin'" }, +] +wheels = [ + { url = "https://files.pythonhosted.org/packages/f1/84/26025437c1e6b61a707442184fa0c03d083b661adf3a3eecfd6d21677740/nvidia_cudnn_cu13-9.19.0.56-py3-none-manylinux_2_27_aarch64.whl", hash = "sha256:6ed29ffaee1176c612daf442e4dd6cfeb6a0caa43ddcbeb59da94953030b1be4", size = 433781201, upload-time = "2026-02-03T20:40:53.805Z" }, + { url = "https://files.pythonhosted.org/packages/a3/22/0b4b932655d17a6da1b92fa92ab12844b053bb2ac2475e179ba6f043da1e/nvidia_cudnn_cu13-9.19.0.56-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:d20e1734305e9d68889a96e3f35094d733ff1f83932ebe462753973e53a572bf", size = 366066321, upload-time = "2026-02-03T20:44:52.837Z" }, +] + +[[package]] +name = "nvidia-cufft" +version = "12.0.0.61" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "nvidia-nvjitlink", marker = "sys_platform != 'darwin'" }, +] +wheels = [ + { url = "https://files.pythonhosted.org/packages/8b/ae/f417a75c0259e85c1d2f83ca4e960289a5f814ed0cea74d18c353d3e989d/nvidia_cufft-12.0.0.61-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:2708c852ef8cd89d1d2068bdbece0aa188813a0c934db3779b9b1faa8442e5f5", size = 214053554, upload-time = "2025-09-04T08:31:38.196Z" }, + { url = "https://files.pythonhosted.org/packages/a8/2f/7b57e29836ea8714f81e9898409196f47d772d5ddedddf1592eadb8ab743/nvidia_cufft-12.0.0.61-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:6c44f692dce8fd5ffd3e3df134b6cdb9c2f72d99cf40b62c32dde45eea9ddad3", size = 214085489, upload-time = "2025-09-04T08:31:56.044Z" }, +] + +[[package]] +name = "nvidia-cufile" +version = "1.15.1.6" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/3f/70/4f193de89a48b71714e74602ee14d04e4019ad36a5a9f20c425776e72cd6/nvidia_cufile-1.15.1.6-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:08a3ecefae5a01c7f5117351c64f17c7c62efa5fffdbe24fc7d298da19cd0b44", size = 1223672, upload-time = "2025-09-04T08:32:22.779Z" }, + { url = "https://files.pythonhosted.org/packages/ab/73/cc4a14c9813a8a0d509417cf5f4bdaba76e924d58beb9864f5a7baceefbf/nvidia_cufile-1.15.1.6-py3-none-manylinux_2_27_aarch64.whl", hash = "sha256:bdc0deedc61f548bddf7733bdc216456c2fdb101d020e1ab4b88d232d5e2f6d1", size = 1136992, upload-time = "2025-09-04T08:32:14.119Z" }, +] + +[[package]] +name = "nvidia-curand" +version = "10.4.0.35" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/1e/72/7c2ae24fb6b63a32e6ae5d241cc65263ea18d08802aaae087d9f013335a2/nvidia_curand-10.4.0.35-py3-none-manylinux_2_27_aarch64.whl", hash = "sha256:133df5a7509c3e292aaa2b477afd0194f06ce4ea24d714d616ff36439cee349a", size = 61962106, upload-time = "2025-08-04T10:21:41.128Z" }, + { url = "https://files.pythonhosted.org/packages/a5/9f/be0a41ca4a4917abf5cb9ae0daff1a6060cc5de950aec0396de9f3b52bc5/nvidia_curand-10.4.0.35-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:1aee33a5da6e1db083fe2b90082def8915f30f3248d5896bcec36a579d941bfc", size = 59544258, upload-time = "2025-08-04T10:22:03.992Z" }, +] + +[[package]] +name = "nvidia-cusolver" +version = "12.0.4.66" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "nvidia-cublas", marker = "sys_platform != 'darwin'" }, + { name = "nvidia-cusparse", marker = "sys_platform != 'darwin'" }, + { name = "nvidia-nvjitlink", marker = "sys_platform != 'darwin'" }, +] +wheels = [ + { url = "https://files.pythonhosted.org/packages/c8/c3/b30c9e935fc01e3da443ec0116ed1b2a009bb867f5324d3f2d7e533e776b/nvidia_cusolver-12.0.4.66-py3-none-manylinux_2_27_aarch64.whl", hash = "sha256:02c2457eaa9e39de20f880f4bd8820e6a1cfb9f9a34f820eb12a155aa5bc92d2", size = 223467760, upload-time = "2025-09-04T08:33:04.222Z" }, + { url = "https://files.pythonhosted.org/packages/5f/67/cba3777620cdacb99102da4042883709c41c709f4b6323c10781a9c3aa34/nvidia_cusolver-12.0.4.66-py3-none-manylinux_2_27_x86_64.whl", hash = "sha256:0a759da5dea5c0ea10fd307de75cdeb59e7ea4fcb8add0924859b944babf1112", size = 200941980, upload-time = "2025-09-04T08:33:22.767Z" }, +] + +[[package]] +name = "nvidia-cusparse" +version = "12.6.3.3" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "nvidia-nvjitlink", marker = "sys_platform != 'darwin'" }, +] +wheels = [ + { url = "https://files.pythonhosted.org/packages/f8/94/5c26f33738ae35276672f12615a64bd008ed5be6d1ebcb23579285d960a9/nvidia_cusparse-12.6.3.3-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:80bcc4662f23f1054ee334a15c72b8940402975e0eab63178fc7e670aa59472c", size = 162155568, upload-time = "2025-09-04T08:33:42.864Z" }, + { url = "https://files.pythonhosted.org/packages/fa/18/623c77619c31d62efd55302939756966f3ecc8d724a14dab2b75f1508850/nvidia_cusparse-12.6.3.3-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:2b3c89c88d01ee0e477cb7f82ef60a11a4bcd57b6b87c33f789350b59759360b", size = 145942937, upload-time = "2025-09-04T08:33:58.029Z" }, +] + +[[package]] +name = "nvidia-cusparselt-cu13" +version = "0.8.0" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/46/10/8dcd1175260706a2fc92a16a52e306b71d4c1ea0b0cc4a9484183399818a/nvidia_cusparselt_cu13-0.8.0-py3-none-manylinux2014_aarch64.whl", hash = "sha256:400c6ed1cf6780fc6efedd64ec9f1345871767e6a1a0a552a1ea0578117ea77c", size = 220791277, upload-time = "2025-08-13T19:22:40.982Z" }, + { url = "https://files.pythonhosted.org/packages/fd/53/43b0d71f4e702fa9733f8b4571fdca50a8813f1e450b656c239beff12315/nvidia_cusparselt_cu13-0.8.0-py3-none-manylinux2014_x86_64.whl", hash = "sha256:25e30a8a7323935d4ad0340b95a0b69926eee755767e8e0b1cf8dd85b197d3fd", size = 169884119, upload-time = "2025-08-13T19:23:41.967Z" }, +] + +[[package]] +name = "nvidia-nccl-cu13" +version = "2.28.9" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/39/55/1920646a2e43ffd4fc958536b276197ed740e9e0c54105b4bb3521591fc7/nvidia_nccl_cu13-2.28.9-py3-none-manylinux_2_18_aarch64.whl", hash = "sha256:01c873ba1626b54caa12272ed228dc5b2781545e0ae8ba3f432a8ef1c6d78643", size = 196561677, upload-time = "2025-11-18T05:49:03.45Z" }, + { url = "https://files.pythonhosted.org/packages/b0/b4/878fefaad5b2bcc6fcf8d474a25e3e3774bc5133e4b58adff4d0bca238bc/nvidia_nccl_cu13-2.28.9-py3-none-manylinux_2_18_x86_64.whl", hash = "sha256:e4553a30f34195f3fa1da02a6da3d6337d28f2003943aa0a3d247bbc25fefc42", size = 196493177, upload-time = "2025-11-18T05:49:17.677Z" }, +] + +[[package]] +name = "nvidia-nvjitlink" +version = "13.0.88" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/56/7a/123e033aaff487c77107195fa5a2b8686795ca537935a24efae476c41f05/nvidia_nvjitlink-13.0.88-py3-none-manylinux2010_x86_64.manylinux_2_12_x86_64.whl", hash = "sha256:13a74f429e23b921c1109976abefacc69835f2f433ebd323d3946e11d804e47b", size = 40713933, upload-time = "2025-09-04T08:35:43.553Z" }, + { url = "https://files.pythonhosted.org/packages/ab/2c/93c5250e64df4f894f1cbb397c6fd71f79813f9fd79d7cd61de3f97b3c2d/nvidia_nvjitlink-13.0.88-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:e931536ccc7d467a98ba1d8b89ff7fa7f1fa3b13f2b0069118cd7f47bff07d0c", size = 38768748, upload-time = "2025-09-04T08:35:20.008Z" }, +] + +[[package]] +name = "nvidia-nvshmem-cu13" +version = "3.4.5" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/dc/0f/05cc9c720236dcd2db9c1ab97fff629e96821be2e63103569da0c9b72f19/nvidia_nvshmem_cu13-3.4.5-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:6dc2a197f38e5d0376ad52cd1a2a3617d3cdc150fd5966f4aee9bcebb1d68fe9", size = 60215947, upload-time = "2025-09-06T00:32:20.022Z" }, + { url = "https://files.pythonhosted.org/packages/3c/35/a9bf80a609e74e3b000fef598933235c908fcefcef9026042b8e6dfde2a9/nvidia_nvshmem_cu13-3.4.5-py3-none-manylinux2014_x86_64.manylinux_2_17_x86_64.whl", hash = "sha256:290f0a2ee94c9f3687a02502f3b9299a9f9fe826e6d0287ee18482e78d495b80", size = 60412546, upload-time = "2025-09-06T00:32:41.564Z" }, +] + +[[package]] +name = "nvidia-nvtx" +version = "13.0.85" +source = { registry = "https://pypi.org/simple" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/c2/f3/d86c845465a2723ad7e1e5c36dcd75ddb82898b3f53be47ebd429fb2fa5d/nvidia_nvtx-13.0.85-py3-none-manylinux1_x86_64.manylinux_2_5_x86_64.whl", hash = "sha256:4936d1d6780fbe68db454f5e72a42ff64d1fd6397df9f363ae786930fd5c1cd4", size = 148047, upload-time = "2025-09-04T08:29:01.761Z" }, + { url = "https://files.pythonhosted.org/packages/a8/64/3708a90d1ebe202ffdeb7185f878a3c84d15c2b2c31858da2ce0583e2def/nvidia_nvtx-13.0.85-py3-none-manylinux2014_aarch64.manylinux_2_17_aarch64.whl", hash = "sha256:cb7780edb6b14107373c835bf8b72e7a178bac7367e23da7acb108f973f157a6", size = 148878, upload-time = "2025-09-04T08:28:53.627Z" }, +] + +[[package]] +name = "opencv-python" +version = "4.10.0.84" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "numpy" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/4a/e7/b70a2d9ab205110d715906fc8ec83fbb00404aeb3a37a0654fdb68eb0c8c/opencv-python-4.10.0.84.tar.gz", hash = "sha256:72d234e4582e9658ffea8e9cae5b63d488ad06994ef12d81dc303b17472f3526", size = 95103981, upload-time = "2024-06-17T18:29:56.757Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/66/82/564168a349148298aca281e342551404ef5521f33fba17b388ead0a84dc5/opencv_python-4.10.0.84-cp37-abi3-macosx_11_0_arm64.whl", hash = "sha256:fc182f8f4cda51b45f01c64e4cbedfc2f00aff799debebc305d8d0210c43f251", size = 54835524, upload-time = "2024-06-18T04:57:32.973Z" }, + { url = "https://files.pythonhosted.org/packages/64/4a/016cda9ad7cf18c58ba074628a4eaae8aa55f3fd06a266398cef8831a5b9/opencv_python-4.10.0.84-cp37-abi3-macosx_12_0_x86_64.whl", hash = "sha256:71e575744f1d23f79741450254660442785f45a0797212852ee5199ef12eed98", size = 56475426, upload-time = "2024-06-17T19:34:10.927Z" }, + { url = "https://files.pythonhosted.org/packages/81/e4/7a987ebecfe5ceaf32db413b67ff18eb3092c598408862fff4d7cc3fd19b/opencv_python-4.10.0.84-cp37-abi3-manylinux_2_17_aarch64.manylinux2014_aarch64.whl", hash = "sha256:09a332b50488e2dda866a6c5573ee192fe3583239fb26ff2f7f9ceb0bc119ea6", size = 41746971, upload-time = "2024-06-17T20:00:25.211Z" }, + { url = "https://files.pythonhosted.org/packages/3f/a4/d2537f47fd7fcfba966bd806e3ec18e7ee1681056d4b0a9c8d983983e4d5/opencv_python-4.10.0.84-cp37-abi3-manylinux_2_17_x86_64.manylinux2014_x86_64.whl", hash = "sha256:9ace140fc6d647fbe1c692bcb2abce768973491222c067c131d80957c595b71f", size = 62548253, upload-time = "2024-06-17T18:29:43.659Z" }, + { url = "https://files.pythonhosted.org/packages/1e/39/bbf57e7b9dab623e8773f6ff36385456b7ae7fa9357a5e53db732c347eac/opencv_python-4.10.0.84-cp37-abi3-win32.whl", hash = "sha256:2db02bb7e50b703f0a2d50c50ced72e95c574e1e5a0bb35a8a86d0b35c98c236", size = 28737688, upload-time = "2024-06-17T18:28:13.177Z" }, + { url = "https://files.pythonhosted.org/packages/ec/6c/fab8113424af5049f85717e8e527ca3773299a3c6b02506e66436e19874f/opencv_python-4.10.0.84-cp37-abi3-win_amd64.whl", hash = "sha256:32dbbd94c26f611dc5cc6979e6b7aa1f55a64d6b463cc1dcd3c95505a63e48fe", size = 38842521, upload-time = "2024-06-17T18:28:21.813Z" }, +] + +[[package]] +name = "packaging" +version = "25.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/a1/d4/1fc4078c65507b51b96ca8f8c3ba19e6a61c8253c72794544580a7b6c24d/packaging-25.0.tar.gz", hash = "sha256:d443872c98d677bf60f6a1f2f8c1cb748e8fe762d2bf9d3148b5599295b0fc4f", size = 165727, upload-time = "2025-04-19T11:48:59.673Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/20/12/38679034af332785aac8774540895e234f4d07f7545804097de4b666afd8/packaging-25.0-py3-none-any.whl", hash = "sha256:29572ef2b1f17581046b3a2227d5c611fb25ec70ca1ba8554b24b0e69331a484", size = 66469, upload-time = "2025-04-19T11:48:57.875Z" }, +] + +[[package]] +name = "pluggy" +version = "1.6.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/f9/e2/3e91f31a7d2b083fe6ef3fa267035b518369d9511ffab804f839851d2779/pluggy-1.6.0.tar.gz", hash = "sha256:7dcc130b76258d33b90f61b658791dede3486c3e6bfb003ee5c9bfb396dd22f3", size = 69412, upload-time = "2025-05-15T12:30:07.975Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/54/20/4d324d65cc6d9205fabedc306948156824eb9f0ee1633355a8f7ec5c66bf/pluggy-1.6.0-py3-none-any.whl", hash = "sha256:e920276dd6813095e9377c0bc5566d94c932c33b27a3e3945d8389c374dd4746", size = 20538, upload-time = "2025-05-15T12:30:06.134Z" }, +] + +[[package]] +name = "pycparser" +version = "3.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/1b/7d/92392ff7815c21062bea51aa7b87d45576f649f16458d78b7cf94b9ab2e6/pycparser-3.0.tar.gz", hash = "sha256:600f49d217304a5902ac3c37e1281c9fe94e4d0489de643a9504c5cdfdfc6b29", size = 103492, upload-time = "2026-01-21T14:26:51.89Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/0c/c3/44f3fbbfa403ea2a7c779186dc20772604442dde72947e7d01069cbe98e3/pycparser-3.0-py3-none-any.whl", hash = "sha256:b727414169a36b7d524c1c3e31839a521725078d7b2ff038656844266160a992", size = 48172, upload-time = "2026-01-21T14:26:50.693Z" }, +] + +[[package]] +name = "pygments" +version = "2.19.2" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/b0/77/a5b8c569bf593b0140bde72ea885a803b82086995367bf2037de0159d924/pygments-2.19.2.tar.gz", hash = "sha256:636cb2477cec7f8952536970bc533bc43743542f70392ae026374600add5b887", size = 4968631, upload-time = "2025-06-21T13:39:12.283Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/c7/21/705964c7812476f378728bdf590ca4b771ec72385c533964653c68e86bdc/pygments-2.19.2-py3-none-any.whl", hash = "sha256:86540386c03d588bb81d44bc3928634ff26449851e99741617ecb9037ee5ec0b", size = 1225217, upload-time = "2025-06-21T13:39:07.939Z" }, +] + +[[package]] +name = "pyparsing" +version = "3.2.5" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/f2/a5/181488fc2b9d093e3972d2a472855aae8a03f000592dbfce716a512b3359/pyparsing-3.2.5.tar.gz", hash = "sha256:2df8d5b7b2802ef88e8d016a2eb9c7aeaa923529cd251ed0fe4608275d4105b6", size = 1099274, upload-time = "2025-09-21T04:11:06.277Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/10/5e/1aa9a93198c6b64513c9d7752de7422c06402de6600a8767da1524f9570b/pyparsing-3.2.5-py3-none-any.whl", hash = "sha256:e38a4f02064cf41fe6593d328d0512495ad1f3d8a91c4f73fc401b3079a59a5e", size = 113890, upload-time = "2025-09-21T04:11:04.117Z" }, +] + +[[package]] +name = "pytest" +version = "9.0.2" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "colorama", marker = "sys_platform == 'win32'" }, + { name = "exceptiongroup" }, + { name = "iniconfig" }, + { name = "packaging" }, + { name = "pluggy" }, + { name = "pygments" }, + { name = "tomli" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/d1/db/7ef3487e0fb0049ddb5ce41d3a49c235bf9ad299b6a25d5780a89f19230f/pytest-9.0.2.tar.gz", hash = "sha256:75186651a92bd89611d1d9fc20f0b4345fd827c41ccd5c299a868a05d70edf11", size = 1568901, upload-time = "2025-12-06T21:30:51.014Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/3b/ab/b3226f0bd7cdcf710fbede2b3548584366da3b19b5021e74f5bde2a8fa3f/pytest-9.0.2-py3-none-any.whl", hash = "sha256:711ffd45bf766d5264d487b917733b453d917afd2b0ad65223959f59089f875b", size = 374801, upload-time = "2025-12-06T21:30:49.154Z" }, +] + +[[package]] +name = "python-dateutil" +version = "2.9.0.post0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "six" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/66/c0/0c8b6ad9f17a802ee498c46e004a0eb49bc148f2fd230864601a86dcf6db/python-dateutil-2.9.0.post0.tar.gz", hash = "sha256:37dd54208da7e1cd875388217d5e00ebd4179249f90fb72437e91a35459a0ad3", size = 342432, upload-time = "2024-03-01T18:36:20.211Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/ec/57/56b9bcc3c9c6a792fcbaf139543cee77261f3651ca9da0c93f5c1221264b/python_dateutil-2.9.0.post0-py2.py3-none-any.whl", hash = "sha256:a8b2bc7bffae282281c8140a97d3aa9c14da0b136dfe83f850eea9a5f7470427", size = 229892, upload-time = "2024-03-01T18:36:18.57Z" }, +] + +[[package]] +name = "pyyaml" +version = "6.0.3" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/05/8e/961c0007c59b8dd7729d542c61a4d537767a59645b82a0b521206e1e25c2/pyyaml-6.0.3.tar.gz", hash = "sha256:d76623373421df22fb4cf8817020cbb7ef15c725b9d5e45f17e189bfc384190f", size = 130960, upload-time = "2025-09-25T21:33:16.546Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/f4/a0/39350dd17dd6d6c6507025c0e53aef67a9293a6d37d3511f23ea510d5800/pyyaml-6.0.3-cp310-cp310-macosx_10_13_x86_64.whl", hash = "sha256:214ed4befebe12df36bcc8bc2b64b396ca31be9304b8f59e25c11cf94a4c033b", size = 184227, upload-time = "2025-09-25T21:31:46.04Z" }, + { url = "https://files.pythonhosted.org/packages/05/14/52d505b5c59ce73244f59c7a50ecf47093ce4765f116cdb98286a71eeca2/pyyaml-6.0.3-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:02ea2dfa234451bbb8772601d7b8e426c2bfa197136796224e50e35a78777956", size = 174019, upload-time = "2025-09-25T21:31:47.706Z" }, + { url = "https://files.pythonhosted.org/packages/43/f7/0e6a5ae5599c838c696adb4e6330a59f463265bfa1e116cfd1fbb0abaaae/pyyaml-6.0.3-cp310-cp310-manylinux2014_aarch64.manylinux_2_17_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:b30236e45cf30d2b8e7b3e85881719e98507abed1011bf463a8fa23e9c3e98a8", size = 740646, upload-time = "2025-09-25T21:31:49.21Z" }, + { url = "https://files.pythonhosted.org/packages/2f/3a/61b9db1d28f00f8fd0ae760459a5c4bf1b941baf714e207b6eb0657d2578/pyyaml-6.0.3-cp310-cp310-manylinux2014_s390x.manylinux_2_17_s390x.manylinux_2_28_s390x.whl", hash = "sha256:66291b10affd76d76f54fad28e22e51719ef9ba22b29e1d7d03d6777a9174198", size = 840793, upload-time = "2025-09-25T21:31:50.735Z" }, + { url = "https://files.pythonhosted.org/packages/7a/1e/7acc4f0e74c4b3d9531e24739e0ab832a5edf40e64fbae1a9c01941cabd7/pyyaml-6.0.3-cp310-cp310-manylinux2014_x86_64.manylinux_2_17_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:9c7708761fccb9397fe64bbc0395abcae8c4bf7b0eac081e12b809bf47700d0b", size = 770293, upload-time = "2025-09-25T21:31:51.828Z" }, + { url = "https://files.pythonhosted.org/packages/8b/ef/abd085f06853af0cd59fa5f913d61a8eab65d7639ff2a658d18a25d6a89d/pyyaml-6.0.3-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:418cf3f2111bc80e0933b2cd8cd04f286338bb88bdc7bc8e6dd775ebde60b5e0", size = 732872, upload-time = "2025-09-25T21:31:53.282Z" }, + { url = "https://files.pythonhosted.org/packages/1f/15/2bc9c8faf6450a8b3c9fc5448ed869c599c0a74ba2669772b1f3a0040180/pyyaml-6.0.3-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:5e0b74767e5f8c593e8c9b5912019159ed0533c70051e9cce3e8b6aa699fcd69", size = 758828, upload-time = "2025-09-25T21:31:54.807Z" }, + { url = "https://files.pythonhosted.org/packages/a3/00/531e92e88c00f4333ce359e50c19b8d1de9fe8d581b1534e35ccfbc5f393/pyyaml-6.0.3-cp310-cp310-win32.whl", hash = "sha256:28c8d926f98f432f88adc23edf2e6d4921ac26fb084b028c733d01868d19007e", size = 142415, upload-time = "2025-09-25T21:31:55.885Z" }, + { url = "https://files.pythonhosted.org/packages/2a/fa/926c003379b19fca39dd4634818b00dec6c62d87faf628d1394e137354d4/pyyaml-6.0.3-cp310-cp310-win_amd64.whl", hash = "sha256:bdb2c67c6c1390b63c6ff89f210c8fd09d9a1217a465701eac7316313c915e4c", size = 158561, upload-time = "2025-09-25T21:31:57.406Z" }, +] + +[[package]] +name = "pyzmq" +version = "27.1.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "cffi", marker = "implementation_name == 'pypy'" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/04/0b/3c9baedbdf613ecaa7aa07027780b8867f57b6293b6ee50de316c9f3222b/pyzmq-27.1.0.tar.gz", hash = "sha256:ac0765e3d44455adb6ddbf4417dcce460fc40a05978c08efdf2948072f6db540", size = 281750, upload-time = "2025-09-08T23:10:18.157Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/67/b9/52aa9ec2867528b54f1e60846728d8b4d84726630874fee3a91e66c7df81/pyzmq-27.1.0-cp310-cp310-macosx_10_15_universal2.whl", hash = "sha256:508e23ec9bc44c0005c4946ea013d9317ae00ac67778bd47519fdf5a0e930ff4", size = 1329850, upload-time = "2025-09-08T23:07:26.274Z" }, + { url = "https://files.pythonhosted.org/packages/99/64/5653e7b7425b169f994835a2b2abf9486264401fdef18df91ddae47ce2cc/pyzmq-27.1.0-cp310-cp310-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:507b6f430bdcf0ee48c0d30e734ea89ce5567fd7b8a0f0044a369c176aa44556", size = 906380, upload-time = "2025-09-08T23:07:29.78Z" }, + { url = "https://files.pythonhosted.org/packages/73/78/7d713284dbe022f6440e391bd1f3c48d9185673878034cfb3939cdf333b2/pyzmq-27.1.0-cp310-cp310-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:bf7b38f9fd7b81cb6d9391b2946382c8237fd814075c6aa9c3b746d53076023b", size = 666421, upload-time = "2025-09-08T23:07:31.263Z" }, + { url = "https://files.pythonhosted.org/packages/30/76/8f099f9d6482450428b17c4d6b241281af7ce6a9de8149ca8c1c649f6792/pyzmq-27.1.0-cp310-cp310-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:03ff0b279b40d687691a6217c12242ee71f0fba28bf8626ff50e3ef0f4410e1e", size = 854149, upload-time = "2025-09-08T23:07:33.17Z" }, + { url = "https://files.pythonhosted.org/packages/59/f0/37fbfff06c68016019043897e4c969ceab18bde46cd2aca89821fcf4fb2e/pyzmq-27.1.0-cp310-cp310-musllinux_1_2_aarch64.whl", hash = "sha256:677e744fee605753eac48198b15a2124016c009a11056f93807000ab11ce6526", size = 1655070, upload-time = "2025-09-08T23:07:35.205Z" }, + { url = "https://files.pythonhosted.org/packages/47/14/7254be73f7a8edc3587609554fcaa7bfd30649bf89cd260e4487ca70fdaa/pyzmq-27.1.0-cp310-cp310-musllinux_1_2_i686.whl", hash = "sha256:dd2fec2b13137416a1c5648b7009499bcc8fea78154cd888855fa32514f3dad1", size = 2033441, upload-time = "2025-09-08T23:07:37.432Z" }, + { url = "https://files.pythonhosted.org/packages/22/dc/49f2be26c6f86f347e796a4d99b19167fc94503f0af3fd010ad262158822/pyzmq-27.1.0-cp310-cp310-musllinux_1_2_x86_64.whl", hash = "sha256:08e90bb4b57603b84eab1d0ca05b3bbb10f60c1839dc471fc1c9e1507bef3386", size = 1891529, upload-time = "2025-09-08T23:07:39.047Z" }, + { url = "https://files.pythonhosted.org/packages/a3/3e/154fb963ae25be70c0064ce97776c937ecc7d8b0259f22858154a9999769/pyzmq-27.1.0-cp310-cp310-win32.whl", hash = "sha256:a5b42d7a0658b515319148875fcb782bbf118dd41c671b62dae33666c2213bda", size = 567276, upload-time = "2025-09-08T23:07:40.695Z" }, + { url = "https://files.pythonhosted.org/packages/62/b2/f4ab56c8c595abcb26b2be5fd9fa9e6899c1e5ad54964e93ae8bb35482be/pyzmq-27.1.0-cp310-cp310-win_amd64.whl", hash = "sha256:c0bb87227430ee3aefcc0ade2088100e528d5d3298a0a715a64f3d04c60ba02f", size = 632208, upload-time = "2025-09-08T23:07:42.298Z" }, + { url = "https://files.pythonhosted.org/packages/3b/e3/be2cc7ab8332bdac0522fdb64c17b1b6241a795bee02e0196636ec5beb79/pyzmq-27.1.0-cp310-cp310-win_arm64.whl", hash = "sha256:9a916f76c2ab8d045b19f2286851a38e9ac94ea91faf65bd64735924522a8b32", size = 559766, upload-time = "2025-09-08T23:07:43.869Z" }, + { url = "https://files.pythonhosted.org/packages/92/e7/038aab64a946d535901103da16b953c8c9cc9c961dadcbf3609ed6428d23/pyzmq-27.1.0-cp312-abi3-macosx_10_15_universal2.whl", hash = "sha256:452631b640340c928fa343801b0d07eb0c3789a5ffa843f6e1a9cee0ba4eb4fc", size = 1306279, upload-time = "2025-09-08T23:08:03.807Z" }, + { url = "https://files.pythonhosted.org/packages/e8/5e/c3c49fdd0f535ef45eefcc16934648e9e59dace4a37ee88fc53f6cd8e641/pyzmq-27.1.0-cp312-abi3-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:1c179799b118e554b66da67d88ed66cd37a169f1f23b5d9f0a231b4e8d44a113", size = 895645, upload-time = "2025-09-08T23:08:05.301Z" }, + { url = "https://files.pythonhosted.org/packages/f8/e5/b0b2504cb4e903a74dcf1ebae157f9e20ebb6ea76095f6cfffea28c42ecd/pyzmq-27.1.0-cp312-abi3-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:3837439b7f99e60312f0c926a6ad437b067356dc2bc2ec96eb395fd0fe804233", size = 652574, upload-time = "2025-09-08T23:08:06.828Z" }, + { url = "https://files.pythonhosted.org/packages/f8/9b/c108cdb55560eaf253f0cbdb61b29971e9fb34d9c3499b0e96e4e60ed8a5/pyzmq-27.1.0-cp312-abi3-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:43ad9a73e3da1fab5b0e7e13402f0b2fb934ae1c876c51d0afff0e7c052eca31", size = 840995, upload-time = "2025-09-08T23:08:08.396Z" }, + { url = "https://files.pythonhosted.org/packages/c2/bb/b79798ca177b9eb0825b4c9998c6af8cd2a7f15a6a1a4272c1d1a21d382f/pyzmq-27.1.0-cp312-abi3-musllinux_1_2_aarch64.whl", hash = "sha256:0de3028d69d4cdc475bfe47a6128eb38d8bc0e8f4d69646adfbcd840facbac28", size = 1642070, upload-time = "2025-09-08T23:08:09.989Z" }, + { url = "https://files.pythonhosted.org/packages/9c/80/2df2e7977c4ede24c79ae39dcef3899bfc5f34d1ca7a5b24f182c9b7a9ca/pyzmq-27.1.0-cp312-abi3-musllinux_1_2_i686.whl", hash = "sha256:cf44a7763aea9298c0aa7dbf859f87ed7012de8bda0f3977b6fb1d96745df856", size = 2021121, upload-time = "2025-09-08T23:08:11.907Z" }, + { url = "https://files.pythonhosted.org/packages/46/bd/2d45ad24f5f5ae7e8d01525eb76786fa7557136555cac7d929880519e33a/pyzmq-27.1.0-cp312-abi3-musllinux_1_2_x86_64.whl", hash = "sha256:f30f395a9e6fbca195400ce833c731e7b64c3919aa481af4d88c3759e0cb7496", size = 1878550, upload-time = "2025-09-08T23:08:13.513Z" }, + { url = "https://files.pythonhosted.org/packages/e6/2f/104c0a3c778d7c2ab8190e9db4f62f0b6957b53c9d87db77c284b69f33ea/pyzmq-27.1.0-cp312-abi3-win32.whl", hash = "sha256:250e5436a4ba13885494412b3da5d518cd0d3a278a1ae640e113c073a5f88edd", size = 559184, upload-time = "2025-09-08T23:08:15.163Z" }, + { url = "https://files.pythonhosted.org/packages/fc/7f/a21b20d577e4100c6a41795842028235998a643b1ad406a6d4163ea8f53e/pyzmq-27.1.0-cp312-abi3-win_amd64.whl", hash = "sha256:9ce490cf1d2ca2ad84733aa1d69ce6855372cb5ce9223802450c9b2a7cba0ccf", size = 619480, upload-time = "2025-09-08T23:08:17.192Z" }, + { url = "https://files.pythonhosted.org/packages/78/c2/c012beae5f76b72f007a9e91ee9401cb88c51d0f83c6257a03e785c81cc2/pyzmq-27.1.0-cp312-abi3-win_arm64.whl", hash = "sha256:75a2f36223f0d535a0c919e23615fc85a1e23b71f40c7eb43d7b1dedb4d8f15f", size = 552993, upload-time = "2025-09-08T23:08:18.926Z" }, + { url = "https://files.pythonhosted.org/packages/f3/81/a65e71c1552f74dec9dff91d95bafb6e0d33338a8dfefbc88aa562a20c92/pyzmq-27.1.0-pp310-pypy310_pp73-macosx_10_15_x86_64.whl", hash = "sha256:c17e03cbc9312bee223864f1a2b13a99522e0dc9f7c5df0177cd45210ac286e6", size = 836266, upload-time = "2025-09-08T23:09:40.048Z" }, + { url = "https://files.pythonhosted.org/packages/58/ed/0202ca350f4f2b69faa95c6d931e3c05c3a397c184cacb84cb4f8f42f287/pyzmq-27.1.0-pp310-pypy310_pp73-manylinux2014_i686.manylinux_2_17_i686.whl", hash = "sha256:f328d01128373cb6763823b2b4e7f73bdf767834268c565151eacb3b7a392f90", size = 800206, upload-time = "2025-09-08T23:09:41.902Z" }, + { url = "https://files.pythonhosted.org/packages/47/42/1ff831fa87fe8f0a840ddb399054ca0009605d820e2b44ea43114f5459f4/pyzmq-27.1.0-pp310-pypy310_pp73-manylinux_2_26_aarch64.manylinux_2_28_aarch64.whl", hash = "sha256:9c1790386614232e1b3a40a958454bdd42c6d1811837b15ddbb052a032a43f62", size = 567747, upload-time = "2025-09-08T23:09:43.741Z" }, + { url = "https://files.pythonhosted.org/packages/d1/db/5c4d6807434751e3f21231bee98109aa57b9b9b55e058e450d0aef59b70f/pyzmq-27.1.0-pp310-pypy310_pp73-manylinux_2_26_x86_64.manylinux_2_28_x86_64.whl", hash = "sha256:448f9cb54eb0cee4732b46584f2710c8bc178b0e5371d9e4fc8125201e413a74", size = 747371, upload-time = "2025-09-08T23:09:45.575Z" }, + { url = "https://files.pythonhosted.org/packages/26/af/78ce193dbf03567eb8c0dc30e3df2b9e56f12a670bf7eb20f9fb532c7e8a/pyzmq-27.1.0-pp310-pypy310_pp73-win_amd64.whl", hash = "sha256:05b12f2d32112bf8c95ef2e74ec4f1d4beb01f8b5e703b38537f8849f92cb9ba", size = 544862, upload-time = "2025-09-08T23:09:47.448Z" }, +] + +[[package]] +name = "requests" +version = "2.32.5" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "certifi" }, + { name = "charset-normalizer" }, + { name = "idna" }, + { name = "urllib3" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/c9/74/b3ff8e6c8446842c3f5c837e9c3dfcfe2018ea6ecef224c710c85ef728f4/requests-2.32.5.tar.gz", hash = "sha256:dbba0bac56e100853db0ea71b82b4dfd5fe2bf6d3754a8893c3af500cec7d7cf", size = 134517, upload-time = "2025-08-18T20:46:02.573Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/1e/db/4254e3eabe8020b458f1a747140d32277ec7a271daf1d235b70dc0b4e6e3/requests-2.32.5-py3-none-any.whl", hash = "sha256:2462f94637a34fd532264295e186976db0f5d453d1cdd31473c85a6a161affb6", size = 64738, upload-time = "2025-08-18T20:46:00.542Z" }, +] + +[[package]] +name = "rospkg" +version = "1.6.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "catkin-pkg" }, + { name = "distro" }, + { name = "pyyaml" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/ca/15/c74423bc434c7b3a8236fdd2af5f4c4ce3b4a5fd081cfa0fc3066c2f2638/rospkg-1.6.0.tar.gz", hash = "sha256:61c87ab60877388c0874c2e89f506b862918e8ca87b7f2949d9991a4add87036", size = 42642, upload-time = "2025-01-24T23:19:14.604Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/fa/c1/b0616243c1f922252ceb4513c22abefc1773cf372bfc0b6f7e59c2829f96/rospkg-1.6.0-py3-none-any.whl", hash = "sha256:491d49a0d85969cd99df056122f95fc33ff277992a4e275c4448c2e02220a9cb", size = 36040, upload-time = "2025-01-24T23:19:12.771Z" }, +] + +[[package]] +name = "setuptools" +version = "80.9.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/18/5d/3bf57dcd21979b887f014ea83c24ae194cfcd12b9e0fda66b957c69d1fca/setuptools-80.9.0.tar.gz", hash = "sha256:f36b47402ecde768dbfafc46e8e4207b4360c654f1f3bb84475f0a28628fb19c", size = 1319958, upload-time = "2025-05-27T00:56:51.443Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/a3/dc/17031897dae0efacfea57dfd3a82fdd2a2aeb58e0ff71b77b87e44edc772/setuptools-80.9.0-py3-none-any.whl", hash = "sha256:062d34222ad13e0cc312a4c02d73f059e86a4acbfbdea8f8f76b28c99f306922", size = 1201486, upload-time = "2025-05-27T00:56:49.664Z" }, +] + +[[package]] +name = "six" +version = "1.17.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/94/e7/b2c673351809dca68a0e064b6af791aa332cf192da575fd474ed7d6f16a2/six-1.17.0.tar.gz", hash = "sha256:ff70335d468e7eb6ec65b95b99d3a2836546063f63acc5171de367e834932a81", size = 34031, upload-time = "2024-12-04T17:35:28.174Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/b7/ce/149a00dd41f10bc29e5921b496af8b574d8413afcd5e30dfa0ed46c2cc5e/six-1.17.0-py2.py3-none-any.whl", hash = "sha256:4721f391ed90541fddacab5acf947aa0d3dc7d27b2e1e8eda2be8970586c3274", size = 11050, upload-time = "2024-12-04T17:35:26.475Z" }, +] + +[[package]] +name = "sympy" +version = "1.14.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "mpmath" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/83/d3/803453b36afefb7c2bb238361cd4ae6125a569b4db67cd9e79846ba2d68c/sympy-1.14.0.tar.gz", hash = "sha256:d3d3fe8df1e5a0b42f0e7bdf50541697dbe7d23746e894990c030e2b05e72517", size = 7793921, upload-time = "2025-04-27T18:05:01.611Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/a2/09/77d55d46fd61b4a135c444fc97158ef34a095e5681d0a6c10b75bf356191/sympy-1.14.0-py3-none-any.whl", hash = "sha256:e091cc3e99d2141a0ba2847328f5479b05d94a6635cb96148ccb3f34671bd8f5", size = 6299353, upload-time = "2025-04-27T18:04:59.103Z" }, +] + +[[package]] +name = "tomli" +version = "2.3.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/52/ed/3f73f72945444548f33eba9a87fc7a6e969915e7b1acc8260b30e1f76a2f/tomli-2.3.0.tar.gz", hash = "sha256:64be704a875d2a59753d80ee8a533c3fe183e3f06807ff7dc2232938ccb01549", size = 17392, upload-time = "2025-10-08T22:01:47.119Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/77/b8/0135fadc89e73be292b473cb820b4f5a08197779206b33191e801feeae40/tomli-2.3.0-py3-none-any.whl", hash = "sha256:e95b1af3c5b07d9e643909b5abbec77cd9f1217e6d0bca72b0234736b9fb1f1b", size = 14408, upload-time = "2025-10-08T22:01:46.04Z" }, +] + +[[package]] +name = "torch" +version = "2.11.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "cuda-bindings", marker = "sys_platform == 'linux'" }, + { name = "cuda-toolkit", extra = ["cublas", "cudart", "cufft", "cufile", "cupti", "curand", "cusolver", "cusparse", "nvjitlink", "nvrtc", "nvtx"], marker = "sys_platform == 'linux'" }, + { name = "filelock" }, + { name = "fsspec" }, + { name = "jinja2" }, + { name = "networkx" }, + { name = "nvidia-cudnn-cu13", marker = "sys_platform == 'linux'" }, + { name = "nvidia-cusparselt-cu13", marker = "sys_platform == 'linux'" }, + { name = "nvidia-nccl-cu13", marker = "sys_platform == 'linux'" }, + { name = "nvidia-nvshmem-cu13", marker = "sys_platform == 'linux'" }, + { name = "setuptools" }, + { name = "sympy" }, + { name = "triton", marker = "sys_platform == 'linux'" }, + { name = "typing-extensions" }, +] +wheels = [ + { url = "https://files.pythonhosted.org/packages/ac/f2/c1690994afe461aae2d0cac62251e6802a703dec0a6c549c02ecd0de92a9/torch-2.11.0-cp310-cp310-macosx_11_0_arm64.whl", hash = "sha256:2c0d7fcfbc0c4e8bb5ebc3907cbc0c6a0da1b8f82b1fc6e14e914fa0b9baf74e", size = 80526521, upload-time = "2026-03-23T18:12:06.86Z" }, + { url = "https://files.pythonhosted.org/packages/a4/f0/98ae802fa8c09d3149b0c8690741f3f5753c90e779bd28c9613257295945/torch-2.11.0-cp310-cp310-manylinux_2_28_aarch64.whl", hash = "sha256:4cf8687f4aec3900f748d553483ef40e0ac38411c3c48d0a86a438f6d7a99b18", size = 419723025, upload-time = "2026-03-23T18:11:43.774Z" }, + { url = "https://files.pythonhosted.org/packages/f9/1e/18a9b10b4bd34f12d4e561c52b0ae7158707b8193c6cfc0aad2b48167090/torch-2.11.0-cp310-cp310-manylinux_2_28_x86_64.whl", hash = "sha256:1b32ceda909818a03b112006709b02be1877240c31750a8d9c6b7bf5f2d8a6e5", size = 530589207, upload-time = "2026-03-23T18:11:23.756Z" }, + { url = "https://files.pythonhosted.org/packages/35/40/2d532e8c0e23705be9d1debce5bc37b68d59a39bda7584c26fe9668076fe/torch-2.11.0-cp310-cp310-win_amd64.whl", hash = "sha256:b3c712ae6fb8e7a949051a953fc412fe0a6940337336c3b6f905e905dac5157f", size = 114518313, upload-time = "2026-03-23T18:11:58.281Z" }, +] + +[[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" }, +] + +[[package]] +name = "typing-extensions" +version = "4.15.0" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/72/94/1a15dd82efb362ac84269196e94cf00f187f7ed21c242792a923cdb1c61f/typing_extensions-4.15.0.tar.gz", hash = "sha256:0cea48d173cc12fa28ecabc3b837ea3cf6f38c6d1136f85cbaaf598984861466", size = 109391, upload-time = "2025-08-25T13:49:26.313Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/18/67/36e9267722cc04a6b9f15c7f3441c2363321a3ea07da7ae0c0707beb2a9c/typing_extensions-4.15.0-py3-none-any.whl", hash = "sha256:f0fa19c6845758ab08074a0cfa8b7aecb71c999ca73d62883bc25cc018c4e548", size = 44614, upload-time = "2025-08-25T13:49:24.86Z" }, +] + +[[package]] +name = "universal-client" +version = "0.1.0" +source = { editable = "." } +dependencies = [ + { name = "numpy" }, + { name = "opencv-python" }, + { name = "pyyaml" }, + { name = "requests" }, + { name = "rospkg" }, + { name = "torch" }, + { name = "zmq" }, +] + +[package.dev-dependencies] +dev = [ + { name = "pytest" }, +] + +[package.metadata] +requires-dist = [ + { name = "numpy", specifier = "<2" }, + { name = "opencv-python", specifier = "<4.11" }, + { name = "pyyaml", specifier = ">=6.0.3" }, + { name = "requests", specifier = ">=2.32.4" }, + { name = "rospkg", specifier = ">=1.6.0" }, + { name = "torch", specifier = ">=2.11.0" }, + { name = "zmq", specifier = ">=0.0.0" }, +] + +[package.metadata.requires-dev] +dev = [{ name = "pytest", specifier = ">=8.3.5" }] + +[[package]] +name = "urllib3" +version = "2.6.1" +source = { registry = "https://pypi.org/simple" } +sdist = { url = "https://files.pythonhosted.org/packages/5e/1d/0f3a93cca1ac5e8287842ed4eebbd0f7a991315089b1a0b01c7788aa7b63/urllib3-2.6.1.tar.gz", hash = "sha256:5379eb6e1aba4088bae84f8242960017ec8d8e3decf30480b3a1abdaa9671a3f", size = 432678, upload-time = "2025-12-08T15:25:26.773Z" } +wheels = [ + { url = "https://files.pythonhosted.org/packages/bc/56/190ceb8cb10511b730b564fb1e0293fa468363dbad26145c34928a60cb0c/urllib3-2.6.1-py3-none-any.whl", hash = "sha256:e67d06fe947c36a7ca39f4994b08d73922d40e6cca949907be05efa6fd75110b", size = 131138, upload-time = "2025-12-08T15:25:25.51Z" }, +] + +[[package]] +name = "zmq" +version = "0.0.0" +source = { registry = "https://pypi.org/simple" } +dependencies = [ + { name = "pyzmq" }, +] +sdist = { url = "https://files.pythonhosted.org/packages/6e/78/833b2808793c1619835edb1a4e17a023d5d625f4f97ff25ffff986d1f472/zmq-0.0.0.tar.gz", hash = "sha256:6b1a1de53338646e8c8405803cffb659e8eb7bb02fff4c9be62a7acfac8370c9", size = 966, upload-time = "2015-05-21T17:34:26.603Z" } diff --git a/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/.gitignore b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/.gitignore new file mode 100644 index 0000000..79f9e97 --- /dev/null +++ b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/.gitignore @@ -0,0 +1,16 @@ +# Python +__pycache__/ +*.py[cod] +*.so +.env +venv/ +*.egg-info/ + +# ROS +build/ +devel/ +logs/ + +# IDE +.vscode/ +.idea/ \ No newline at end of file diff --git a/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/README.md b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/README.md new file mode 100644 index 0000000..a708887 --- /dev/null +++ b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/README.md @@ -0,0 +1,2 @@ +# robodriver-robot-linkerbot-aio-dora +用于接入智源数据采集平台,写的robodriver node diff --git a/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/lerobot_robot_linkerbot_aio_ros1/__init__.py b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/lerobot_robot_linkerbot_aio_ros1/__init__.py new file mode 100644 index 0000000..3b260e9 --- /dev/null +++ b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/lerobot_robot_linkerbot_aio_ros1/__init__.py @@ -0,0 +1 @@ +from robodriver_robot_linkerbot_aio_ros1 import * \ No newline at end of file diff --git a/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/pyproject.toml b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/pyproject.toml new file mode 100644 index 0000000..6450d62 --- /dev/null +++ b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/pyproject.toml @@ -0,0 +1,21 @@ +[build-system] +requires = ["setuptools>=61.0"] +build-backend = "setuptools.build_meta" + +[project] +name = "robodriver_robot_linkerbot_aio_ros1" +version = "0.1.0" +readme = "README.md" +requires-python = ">=3.10" +license = { text = "Apache-2.0" } +keywords = ["robotics", "lerobot", "linkerbot_aio_ros1"] + +dependencies = [ + "logging_mp", + "numpy", + "pyzmq", + "opencv-python", +] + +[tool.setuptools.packages.find] +include = ["robodriver_robot_linkerbot_aio_ros1", "lerobot_robot_linkerbot_aio_ros1"] \ No newline at end of file diff --git a/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/__init__.py b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/__init__.py new file mode 100644 index 0000000..72fa83a --- /dev/null +++ b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/__init__.py @@ -0,0 +1,3 @@ +from .robot import LinkerBotAioRos1Robot +from .node import LinkerBotAioRos1Node +from .config import LinkerBotAioRos1RobotConfig \ No newline at end of file diff --git a/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/config.py b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/config.py new file mode 100644 index 0000000..0681d9c --- /dev/null +++ b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/config.py @@ -0,0 +1,154 @@ +from typing import Dict +from dataclasses import dataclass, field + +from lerobot.robots.config import RobotConfig +from lerobot.cameras import CameraConfig +from lerobot.cameras.opencv import OpenCVCameraConfig +from lerobot.motors import Motor, MotorNormMode + + +@RobotConfig.register_subclass("linkerbot_aio_ros1") +@dataclass +class LinkerBotAioRos1RobotConfig(RobotConfig): + use_degrees = True + norm_mode_body = ( + MotorNormMode.DEGREES if use_degrees else MotorNormMode.RANGE_M100_100 + ) + + + follower_motors: Dict[str, Dict[str, Motor]] = field( + default_factory=lambda norm_mode_body=norm_mode_body: { + "follower_left_joints": { + "joint_1": Motor(1, "robot_motor", norm_mode_body), + "joint_2": Motor(2, "robot_motor", norm_mode_body), + "joint_3": Motor(3, "robot_motor", norm_mode_body), + "joint_4": Motor(4, "robot_motor", norm_mode_body), + "joint_5": Motor(5, "robot_motor", norm_mode_body), + "joint_6": Motor(6, "robot_motor", norm_mode_body), + "joint_7": Motor(7, "robot_motor", norm_mode_body), + }, + "follower_right_joints": { + "joint_1": Motor(1, "robot_motor", norm_mode_body), + "joint_2": Motor(2, "robot_motor", norm_mode_body), + "joint_3": Motor(3, "robot_motor", norm_mode_body), + "joint_4": Motor(4, "robot_motor", norm_mode_body), + "joint_5": Motor(5, "robot_motor", norm_mode_body), + "joint_6": Motor(6, "robot_motor", norm_mode_body), + "joint_7": Motor(7, "robot_motor", norm_mode_body), + }, + "follower_left_hand": { + "joint_1": Motor(1, "robot_motor", norm_mode_body), + "joint_2": Motor(2, "robot_motor", norm_mode_body), + "joint_3": Motor(3, "robot_motor", norm_mode_body), + "joint_4": Motor(4, "robot_motor", norm_mode_body), + "joint_5": Motor(5, "robot_motor", norm_mode_body), + "joint_6": Motor(6, "robot_motor", norm_mode_body), + "joint_7": Motor(7, "robot_motor", norm_mode_body), + "joint_8": Motor(8, "robot_motor", norm_mode_body), + "joint_9": Motor(9, "robot_motor", norm_mode_body), + "joint_10": Motor(10, "robot_motor", norm_mode_body), + }, + "follower_right_hand": { + "joint_1": Motor(1, "robot_motor", norm_mode_body), + "joint_2": Motor(2, "robot_motor", norm_mode_body), + "joint_3": Motor(3, "robot_motor", norm_mode_body), + "joint_4": Motor(4, "robot_motor", norm_mode_body), + "joint_5": Motor(5, "robot_motor", norm_mode_body), + "joint_6": Motor(6, "robot_motor", norm_mode_body), + "joint_7": Motor(7, "robot_motor", norm_mode_body), + "joint_8": Motor(8, "robot_motor", norm_mode_body), + "joint_9": Motor(9, "robot_motor", norm_mode_body), + "joint_10": Motor(10, "robot_motor", norm_mode_body), + }, + "follower_left_pose": { + "pose_position_x": Motor(1, "robot_motor", norm_mode_body), + "pose_position_y": Motor(2, "robot_motor", norm_mode_body), + "pose_position_z": Motor(3, "robot_motor", norm_mode_body), + "pose_oriention_x": Motor(4, "robot_motor", norm_mode_body), + "pose_oriention_y": Motor(5, "robot_motor", norm_mode_body), + "pose_oriention_z": Motor(6, "robot_motor", norm_mode_body), + "pose_oriention_w": Motor(7, "robot_motor", norm_mode_body), + }, + "follower_right_pose": { + "pose_position_x": Motor(1, "robot_motor", norm_mode_body), + "pose_position_y": Motor(2, "robot_motor", norm_mode_body), + "pose_position_z": Motor(3, "robot_motor", norm_mode_body), + "pose_oriention_x": Motor(4, "robot_motor", norm_mode_body), + "pose_oriention_y": Motor(5, "robot_motor", norm_mode_body), + "pose_oriention_z": Motor(6, "robot_motor", norm_mode_body), + "pose_oriention_w": Motor(7, "robot_motor", norm_mode_body), + }, + } + ) + leader_motors: Dict[str, Dict[str, Motor]] = field( + default_factory=lambda norm_mode_body=norm_mode_body: { + "leader_left_joints": { + "joint_1": Motor(1, "robot_motor", norm_mode_body), + "joint_2": Motor(2, "robot_motor", norm_mode_body), + "joint_3": Motor(3, "robot_motor", norm_mode_body), + "joint_4": Motor(4, "robot_motor", norm_mode_body), + "joint_5": Motor(5, "robot_motor", norm_mode_body), + "joint_6": Motor(6, "robot_motor", norm_mode_body), + "joint_7": Motor(7, "robot_motor", norm_mode_body), + }, + "leader_right_joints": { + "joint_1": Motor(1, "robot_motor", norm_mode_body), + "joint_2": Motor(2, "robot_motor", norm_mode_body), + "joint_3": Motor(3, "robot_motor", norm_mode_body), + "joint_4": Motor(4, "robot_motor", norm_mode_body), + "joint_5": Motor(5, "robot_motor", norm_mode_body), + "joint_6": Motor(6, "robot_motor", norm_mode_body), + "joint_7": Motor(7, "robot_motor", norm_mode_body), + }, + "leader_left_hand": { + "thumb_spread": Motor(1, "robot_motor", norm_mode_body), + "thumb_bend": Motor(2, "robot_motor", norm_mode_body), + "thumb_tip": Motor(3, "robot_motor", norm_mode_body), + "index_spread": Motor(4, "robot_motor", norm_mode_body), + "index_bend": Motor(5, "robot_motor", norm_mode_body), + "index_tip": Motor(6, "robot_motor", norm_mode_body), + "middle_spread": Motor(7, "robot_motor", norm_mode_body), + "middle_bend": Motor(8, "robot_motor", norm_mode_body), + "middle_tip": Motor(9, "robot_motor", norm_mode_body), + "ring_spread": Motor(10, "robot_motor", norm_mode_body), + "ring_bend": Motor(11, "robot_motor", norm_mode_body), + "ring_tip": Motor(12, "robot_motor", norm_mode_body), + "pinky_spread": Motor(13, "robot_motor", norm_mode_body), + "pinky_bend": Motor(14, "robot_motor", norm_mode_body), + "pinky_tip": Motor(15, "robot_motor", norm_mode_body), + }, + "leader_right_hand": { + "thumb_spread": Motor(1, "robot_motor", norm_mode_body), + "thumb_bend": Motor(2, "robot_motor", norm_mode_body), + "thumb_tip": Motor(3, "robot_motor", norm_mode_body), + "index_spread": Motor(4, "robot_motor", norm_mode_body), + "index_bend": Motor(5, "robot_motor", norm_mode_body), + "index_tip": Motor(6, "robot_motor", norm_mode_body), + "middle_spread": Motor(7, "robot_motor", norm_mode_body), + "middle_bend": Motor(8, "robot_motor", norm_mode_body), + "middle_tip": Motor(9, "robot_motor", norm_mode_body), + "ring_spread": Motor(10, "robot_motor", norm_mode_body), + "ring_bend": Motor(11, "robot_motor", norm_mode_body), + "ring_tip": Motor(12, "robot_motor", norm_mode_body), + "pinky_spread": Motor(13, "robot_motor", norm_mode_body), + "pinky_bend": Motor(14, "robot_motor", norm_mode_body), + "pinky_tip": Motor(15, "robot_motor", norm_mode_body), + }, + } + ) + + cameras: Dict[str, CameraConfig] = field( + default_factory=lambda: { + "image_top": OpenCVCameraConfig( + index_or_path=1, + fps=10, + width=640, + height=480, + ), + } + ) + + use_videos: bool = False + + microphones: Dict[str, int] = field(default_factory=lambda: {} + ) \ No newline at end of file diff --git a/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/node.py b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/node.py new file mode 100644 index 0000000..c947e60 --- /dev/null +++ b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/node.py @@ -0,0 +1,176 @@ +# robodriver_robot_linkerbot_aio_ros1/node.py + +import threading +from typing import Dict + +import cv2 +import numpy as np +import zmq +import pickle +import json +import logging_mp + +logger = logging_mp.get_logger(__name__) + +# 超时计数器初始值 +CONNECT_TIMEOUT_FRAME = 10 + +class LinkerBotAioRos1Node: + """ + 第 2 部分:ZMQ → 本地数据存储 + - [优化] 移除了静态 CONFIG,现在的节点是自适应的。 + - 只要 ZMQ 发送端发来什么名字的数据,这里就自动缓存什么。 + """ + + def __init__( + self, + zmq_endpoint: str = "tcp://127.0.0.1:6000", + zmq_cmd_endpoint: str = "tcp://127.0.0.1:5556" + # 原有的 topic 配置参数已移除,实现配置解耦 + ): + # ---------- 本地缓存 (对外接口) ---------- + # 结构: name -> numpy_array + self.recv_images: Dict[str, np.ndarray] = {} + self.recv_images_status: Dict[str, int] = {} + + self.recv_follower: Dict[str, np.ndarray] = {} + self.recv_follower_status: Dict[str, int] = {} + + self.recv_leader: Dict[str, np.ndarray] = {} + self.recv_leader_status: Dict[str, int] = {} + + # ---------- 内部状态 ---------- + self.lock = threading.Lock() + self.running = False + + # ---------- ZMQ 连接 ---------- + self._ctx = zmq.Context.instance() + self._socket = self._ctx.socket(zmq.SUB) + self._socket.connect(zmq_endpoint) + self._socket.setsockopt_string(zmq.SUBSCRIBE, "") # 订阅所有消息 + + logger.info(f"[ZMQ Node] LinkerBotAioRos1Node connected to {zmq_endpoint}") + + self.spin_thread = None + + self._cmd_socket = self._ctx.socket(zmq.PUB) + # 注意这里是 connect 而不是 bind,因为 Repo 1 的 Hub 已经 bind 了 5556 + self._cmd_socket.connect(zmq_cmd_endpoint) + logger.info(f"[ZMQ Node] Command publisher connected to {zmq_cmd_endpoint}") + + def start(self): + """启动 ZMQ 接收线程""" + if self.running: + return + + self.running = True + self.spin_thread = threading.Thread(target=self._spin_loop, daemon=True) + self.spin_thread.start() + + logger.info("[ZMQ Node] Node started (receiver thread running)") + + def stop(self): + """停止 ZMQ 接收线程""" + if not self.running: + return + + self.running = False + + if self.spin_thread is not None: + self.spin_thread.join(timeout=1.0) + + try: + self._socket.close(0) + except Exception: + pass + + logger.info("[ZMQ Node] Node stopped.") + + def _spin_loop(self): + """ + 后台轮询逻辑 (保持原架构不变) + """ + poller = zmq.Poller() + poller.register(self._socket, zmq.POLLIN) + + while self.running: + try: + socks = dict(poller.poll(timeout=100)) # 100 ms + except zmq.ZMQError as e: + logger.error(f"[ZMQ Node] Poll error: {e}") + break + + if self._socket in socks and socks[self._socket] == zmq.POLLIN: + try: + # 接收多帧消息: [topic, payload] + topic_b, payload_b = self._socket.recv_multipart(flags=zmq.NOBLOCK) + except zmq.Again: + continue + except Exception as e: + logger.error(f"[ZMQ Node] recv_multipart error: {e}") + continue + + try: + # 反序列化 + payload = pickle.loads(payload_b) + self._handle_payload(payload) + except Exception as e: + logger.error(f"[ZMQ Node] payload decode error: {e}") + + def _handle_payload(self, payload: dict): + """ + 处理逻辑: + 这里会自动匹配发送端发来的 kind 和 name,无需查表。 + """ + kind = payload.get("kind") + name = payload.get("name") + # print(f"get:{name}") + if kind is None or name is None: + return + + with self.lock: + # 1. 图像数据 + if kind == "camera": + frame = payload.get("frame") + if frame is not None: + self.recv_images[name] = frame + self.recv_images_status[name] = CONNECT_TIMEOUT_FRAME + + # 2. 机械臂/从手数据 (匹配 kind="follower_joint" / "follower_pose") + elif kind.startswith("follower_"): + values = payload.get("values") + if values is not None: + vec = np.asarray(values, dtype=float) + self.recv_follower[name] = vec + self.recv_follower_status[name] = CONNECT_TIMEOUT_FRAME + + # 3. 主手/遥控数据 (匹配 kind="leader_joint" / "leader_pose") + elif kind.startswith("leader_"): + values = payload.get("values") + if values is not None: + vec = np.asarray(values, dtype=float) + self.recv_leader[name] = vec + self.recv_leader_status[name] = CONNECT_TIMEOUT_FRAME + + else: + # 仅在调试时开启,避免刷屏 + # logger.debug(f"[ZMQ Node] Unhandled kind={kind}, name={name}") + pass + + def send_control_command(self, device_key: str, positions: list): + """ + 向底层发送控制指令 + :param device_key: 对应 settings.yaml 中的 key,比如 "leader_left_joints" + :param positions: 目标角度列表 + """ + payload = { + "device_key": device_key, + "command": { + "position": positions + } + } + try: + # Repo 1 的 _receive_loop 期望直接收到 JSON 字符串 + self._cmd_socket.send_string(json.dumps(payload)) + except Exception as e: + logger.error(f"[ZMQ Node] Failed to send command: {e}") \ No newline at end of file diff --git a/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/robot.py b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/robot.py new file mode 100644 index 0000000..44d0fac --- /dev/null +++ b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/robot.py @@ -0,0 +1,419 @@ +import time +from functools import cached_property +from typing import Any +import math +import numpy as np +import logging_mp + +from lerobot.cameras import make_cameras_from_configs +from lerobot.utils.errors import DeviceNotConnectedError, DeviceAlreadyConnectedError +from lerobot.robots.robot import Robot + +from .config import LinkerBotAioRos1RobotConfig +from .node import LinkerBotAioRos1Node +from .status import LinkerBotAioRos1RobotStatus + +logger = logging_mp.get_logger(__name__) + + +class LinkerBotAioRos1Robot(Robot): + config_class = LinkerBotAioRos1RobotConfig + name = "linkerbot_aio_ros1" + + def __init__(self, config: LinkerBotAioRos1RobotConfig): + super().__init__(config) + self.config = config + self.robot_type = self.config.type + self.use_videos = self.config.use_videos + self.microphones = self.config.microphones + + self.follower_motors = config.follower_motors + self.leader_motors = config.leader_motors + self.cameras = make_cameras_from_configs(self.config.cameras) + + self.connect_excluded_cameras = ["image_pika_pose"] + + self.status = LinkerBotAioRos1RobotStatus() + self.robot_ros1_node = LinkerBotAioRos1Node() + self.robot_ros1_node.start() + + self.connected = False + self.logs = {} + + + # ========= 数据处理核心逻辑========= + + def _get_hardware_info(self, comp_name: str): + """辅助函数:获取硬件配置""" + is_leader = "leader" in comp_name.lower() + is_hand = "hand" in comp_name.lower() + + if is_hand: + status_name = "leader_hand" if is_leader else "follower_hand" + return next((h for h in self.status.specifications.hand.information if h.name == status_name), None) + else: + status_name = "leader_arm" if is_leader else "follower_arm" + return next((a for a in self.status.specifications.arm.information if a.name == status_name), None) + + def _process_incoming(self, raw_val: float, comp_name: str, joint_idx: int) -> float: + """接收时调用:Raw -> 0~1 / 弧度""" + info = self._get_hardware_info(comp_name) + if not info: + return raw_val # 查不到配置直接透传保平安 + + is_hand = "hand" in comp_name.lower() + + if is_hand: + v_max = float(info.joint_p_limit[joint_idx]) + v_min = float(info.joint_n_limit[joint_idx]) + + if v_max == v_min: + norm = 0.5 + else: + norm = (raw_val - v_min) / (v_max - v_min) + + norm = float(np.clip(norm, 0.0, 1.0)) + + # 使用配置变量决定是否反转 (1.0 - norm) + return 1.0 - norm if info.invert_direction else norm + + else: + # 机械臂:使用配置变量决定是否转弧度 + val_in_rad = raw_val if info.is_radian else math.radians(raw_val) + + # 使用配置变量决定是否反转符号 + return -val_in_rad if info.invert_direction else val_in_rad + + def _process_outgoing(self, ml_val: float, comp_name: str, joint_idx: int) -> float: + """下发时调用:0~1 / 弧度 -> Raw""" + info = self._get_hardware_info(comp_name) + if not info: + return ml_val + + is_hand = "hand" in comp_name.lower() + + if is_hand: + v_max = float(info.joint_p_limit[joint_idx]) + v_min = float(info.joint_n_limit[joint_idx]) + + norm = float(np.clip(ml_val, 0.0, 1.0)) + + # 撤销反转 + if info.invert_direction: + norm = 1.0 - norm + + return norm * (v_max - v_min) + v_min + + else: + # 撤销反转 + rad_val = -ml_val if info.invert_direction else ml_val + + # 撤销弧度转换 + return rad_val if info.is_radian else math.degrees(rad_val) + # ========= features ========= + def _generate_feature_name(self, role_prefix: str, comp_name: str, joint_name: str) -> str: + """ + 改进的特征键名生成器:保留完整关节名,防止重名覆盖 + """ + side = 'left' if 'left' in comp_name.lower() else 'right' + + # 1. 如果是位姿数据 (Pose) + if 'pose' in comp_name.lower(): + # 保留 position_x 等完整描述 + suffix = joint_name.replace("pose_", "") + return f"{role_prefix}_{side}_pose_{suffix}" + + # 2. 如果是灵巧手 (Hand) + elif 'hand' in comp_name.lower(): + # 不要 split('_')[-1],直接用 thumb_spread 这样的完整名字 + # 或者如果你想统一格式,可以去掉 joint_ 前缀 + clean_joint_name = joint_name.replace("joint_", "") + return f"{role_prefix}_{side}_hand_{clean_joint_name}.pos" + + # 3. 默认认为是机械臂关节 (Arm) + else: + # 将 joint_1 转为 1 + clean_joint_name = joint_name.replace("joint_", "") + return f"{role_prefix}_{side}_arm_{clean_joint_name}.pos" + + @property + def _follower_motors_ft(self) -> dict[str, type]: + return { + self._generate_feature_name("follower", comp_name, joint_name): float + for comp_name, joints in self.follower_motors.items() + for joint_name in joints + } + + @property + def _leader_motors_ft(self) -> dict[str, type]: + return { + self._generate_feature_name("leader", comp_name, joint_name): float + for comp_name, joints in self.leader_motors.items() + for joint_name in joints + } + + @property + def _cameras_ft(self) -> dict[str, tuple]: + return { + cam: ( + self.config.cameras[cam].height, + self.config.cameras[cam].width, + 3, + ) + for cam in self.cameras + } + + @cached_property + def observation_features(self) -> dict[str, Any]: + return {**self._follower_motors_ft, **self._cameras_ft} + + @cached_property + def action_features(self) -> dict[str, Any]: + return self._leader_motors_ft # 拿不到主臂数据暂时用从臂 + + @property + def is_connected(self) -> bool: + return self.connected + + # ========= connect / disconnect ========= + + def connect(self): + timeout = 20 + start_time = time.perf_counter() + + if self.connected: + raise DeviceAlreadyConnectedError(f"{self} already connected") + + node = self.robot_ros1_node + conditions = [ + # 摄像头图像 (原样保留) + ( + lambda: all( + name in node.recv_images + for name in self.cameras + if name not in self.connect_excluded_cameras + ), + lambda: [ + name + for name in self.cameras + if name not in node.recv_images + and name not in self.connect_excluded_cameras + ], + "等待摄像头图像超时", + ), + # 从臂 (原样保留) + ( + lambda: all( + any(name in key for key in node.recv_follower) + for name in self.follower_motors + ), + lambda: [ + name + for name in self.follower_motors + if not any(name in key for key in node.recv_follower) + ], + "等待从臂数据超时", + ), + ] + + # === 新增:如果配置了主臂,则等待主臂数据 === + if self.leader_motors: + conditions.append(( + lambda: all( + any(name in key for key in getattr(node, "recv_leader", {})) + for name in self.leader_motors + ), + lambda: [ + name + for name in self.leader_motors + if not any(name in key for key in getattr(node, "recv_leader", {})) + ], + "等待主臂数据超时", + )) + + completed = [False] * len(conditions) + + while True: + for i, (cond, _get_missing, _msg) in enumerate(conditions): + if not completed[i] and cond(): + completed[i] = True + + if all(completed): + break + + if time.perf_counter() - start_time > timeout: + failed_messages = [] + for i, (cond, get_missing, base_msg) in enumerate(conditions): + if completed[i]: + continue + + missing = get_missing() + if cond() or not missing: + completed[i] = True + continue + + if i == 0: + received = [name for name in self.cameras if name not in missing] + elif i == 1: + received = [name for name in self.follower_motors if name not in missing] + else: + received = [name for name in self.leader_motors if name not in missing] + + msg = ( + f"{base_msg}: 未收到 [{', '.join(missing)}]; " + f"已收到 [{', '.join(received)}]" + ) + failed_messages.append(msg) + + if not failed_messages: + break + + raise TimeoutError( + f"连接超时,未满足的条件: {'; '.join(failed_messages)}" + ) + + time.sleep(0.01) + + # 成功日志 + success_messages = [] + + if conditions[0][0](): + cam_received = [ + name + for name in self.cameras + if name in node.recv_images + and name not in self.connect_excluded_cameras + ] + success_messages.append(f"摄像头: {', '.join(cam_received)}") + + if conditions[1][0](): + follower_received = [ + name + for name in self.follower_motors + if any(name in key for key in node.recv_follower) + ] + success_messages.append(f"从臂数据: {', '.join(follower_received)}") + + # === 新增:主臂成功日志 === + if self.leader_motors and conditions[2][0](): + leader_received = [ + name + for name in self.leader_motors + if any(name in key for key in getattr(node, "recv_leader", {})) + ] + success_messages.append(f"主臂数据: {', '.join(leader_received)}") + + log_message = "\n[连接成功] 所有设备已就绪:\n" + log_message += "\n".join(f" - {msg}" for msg in success_messages) + log_message += f"\n 总耗时: {time.perf_counter() - start_time:.2f} 秒\n" + logger.info(log_message) + + self.connected = True + + def disconnect(self): + if not self.connected: + raise DeviceNotConnectedError() + self.connected = False + + def __del__(self): + if getattr(self, "connected", False): + self.disconnect() + + # ========= calibrate / configure ========= + + def calibrate(self): + pass + + def configure(self): + pass + + @property + def is_calibrated(self): + return True + + # ========= obs / action ========= + + def get_observation(self) -> dict[str, Any]: + if not self.connected: + raise DeviceNotConnectedError(f"{self} is not connected.") + + start = time.perf_counter() + obs_dict: dict[str, Any] = {} + + node = self.robot_ros1_node + # follower joints + for comp_name, joints in self.follower_motors.items(): + vec = node.recv_follower.get(comp_name) + if vec is None: + continue + joint_names = list(joints.keys()) + for idx, joint in enumerate(joint_names): + if idx >= len(vec): + break + key_name = self._generate_feature_name("follower", comp_name, joint) + obs_dict[key_name] = self._process_incoming(float(vec[idx]), comp_name, idx) + + dt_ms = (time.perf_counter() - start) * 1e3 + logger.debug(f"{self} read follower state: {dt_ms:.1f} ms") + # camera images + for cam_key, _cam in self.cameras.items(): + start = time.perf_counter() + for name, val in node.recv_images.items(): + if cam_key == name or cam_key in name: + obs_dict[cam_key] = val + break + dt_ms = (time.perf_counter() - start) * 1e3 + logger.debug(f"{self} read {cam_key}: {dt_ms:.1f} ms") + return obs_dict + + def get_action(self) -> dict[str, Any]: + if not self.connected: + raise DeviceNotConnectedError(f"{self} is not connected.") + + start = time.perf_counter() + act_dict: dict[str, Any] = {} + + node = self.robot_ros1_node + + for comp_name, joints in self.leader_motors.items(): + vec = node.recv_leader.get(comp_name) + if vec is None: + continue + joint_names = list(joints.keys()) + for idx, joint in enumerate(joint_names): + if idx >= len(vec): + break + key_name = self._generate_feature_name("leader", comp_name, joint) + act_dict[key_name] = self._process_incoming(float(vec[idx]), comp_name, idx) + + dt_ms = (time.perf_counter() - start) * 1e3 + logger.debug(f"{self} read action: {dt_ms:.1f} ms") + return act_dict + + # ========= send_action ========= + + + def send_action(self, action: dict[str, Any]) -> dict[str, Any]: + """The provided action is expected to be a vector.""" + if not self.is_connected: + raise DeviceNotConnectedError( + f"{self} is not connected. You need to run `robot.connect()`." + ) + + # 遍历下发目标 + for comp_name, joints in self.follower_motors.items(): + comp_positions = [] + joint_names = list(joints.keys()) + for idx, joint_name in enumerate(joint_names): + feature_key = self._generate_feature_name("follower", comp_name, joint_name) + + if feature_key in action: + ml_val = float(action[feature_key]) + # 【修改点】:将标准特征还原为底层 Raw 格式 + real_val = self._process_outgoing(ml_val, comp_name, idx) + comp_positions.append(real_val) + + if comp_positions: + self.robot_ros1_node.send_control_command(comp_name, comp_positions) + + return {f"{arm_motor}.pos": val for arm_motor, val in action.items()} \ No newline at end of file diff --git a/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/status.py b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/status.py new file mode 100644 index 0000000..f6a6b48 --- /dev/null +++ b/robodriver/robots/robodriver-robot-linkerbot-aio-ros1-main/robodriver_robot_linkerbot_aio_ros1/status.py @@ -0,0 +1,166 @@ +from dataclasses import dataclass, field, asdict +from typing import List, Optional +import json +import abc +import draccus +import numpy as np + +@dataclass +class CameraInfo: + name: str = "" + chinese_name: str = "" + type: str = "" + width: int = 0 + height: int = 0 + is_connect: bool = False + +@dataclass +class CameraStatus: + number: int = 0 + information: List[CameraInfo] = field(default_factory=list) + + def __post_init__(self): + if not self.information: # 如果 information 为空,则 number 设为 0 + self.number = 0 + else: + self.number = len(self.information) + +@dataclass +class ArmInfo: + name: str = "" + type: str = "" + start_pose: List[float] = field(default_factory=list) + joint_p_limit: List[float] = field(default_factory=list) + joint_n_limit: List[float] = field(default_factory=list) + is_connect: bool = False + invert_direction: bool = False # 新增:是否反转运动方向 + is_radian: bool = False # 新增:底层数据是否已经是弧度 + +@dataclass +class ArmStatus: + number: int = 0 + information: List[ArmInfo] = field(default_factory=list) + + def __post_init__(self): + if not self.information: # 如果 information 为空,则 number 设为 0 + self.number = 0 + else: + self.number = len(self.information) + +@dataclass +class HandInfo: + name: str = "" + type: str = "" + joint_p_limit: List[float] = field(default_factory=list) + joint_n_limit: List[float] = field(default_factory=list) + is_connect: bool = False + invert_direction: bool = False + +@dataclass +class HandStatus: + number: int = 0 + information: List[HandInfo] = field(default_factory=list) + + def __post_init__(self): + if not self.information: + self.number = 0 + else: + self.number = len(self.information) + +@dataclass +class Specifications: + end_type: str = "Default" + fps: int = 30 + camera: Optional[CameraStatus] = None + arm: Optional[ArmStatus] = None + hand: Optional[HandStatus] = None + +@dataclass +class RobotStatus(draccus.ChoiceRegistry, abc.ABC): + device_name: str = "Default" + device_body: str = "Default" + specifications: Specifications = field(default_factory=Specifications) + + @property + def type(self) -> str: + return self.get_choice_name(self.__class__) + + def to_dict(self) -> dict: + return asdict(self) + + def to_json(self) -> str: + return json.dumps(self.to_dict(), ensure_ascii=False) + + +@RobotStatus.register_subclass("linkerbot_aio_ros1") +@dataclass +class LinkerBotAioRos1RobotStatus(RobotStatus): + device_name: str = "linkerbot" + device_body: str = "linkerbot" + + def __post_init__(self): + self.specifications.end_type = "5指灵巧手" + self.specifications.fps = 30 + self.specifications.camera = CameraStatus( + information=[ + CameraInfo( + name="image_head", + chinese_name="腕部摄像头", + type="单目视觉相机", + width=640, + height=480, + is_connect=False + ), + + ] + ) + + self.specifications.arm = ArmStatus( + information=[ + + ArmInfo( + name="follower_arm", + type="linkerbot 从臂 7DOF", + start_pose=[], + joint_p_limit = [np.pi] * 7, # 填入从臂真实的物理限位 + joint_n_limit = [-np.pi] * 7, + is_connect=False, + invert_direction=False, # 从臂不反转 + is_radian=True # 从臂是弧度 + ), + ArmInfo( + name="leader_arm", + type="主控臂 7DOF", + start_pose=[], + # 填入主臂真实的物理限位 + joint_p_limit = [180.0]*7, + joint_n_limit = [-180.0]*7, + is_connect=False, + invert_direction=True, # 主臂动作相反,需要反转 + is_radian=False # 主臂是角度 + ), + + ] + ) + self.specifications.hand = HandStatus( + information=[ + HandInfo( + name="follower_hand", + type="从端灵巧手 10DOF", + # 从手真实限位:0 到 255 + joint_p_limit = [255.0] * 10, + joint_n_limit = [0.0] * 10, + is_connect=False, + invert_direction=False + ), + HandInfo( + name="leader_hand", + type="遥操作主手 15DOF", + # 主手真实限位:-65535 到 65535 + joint_p_limit = [65535.0] * 15, + joint_n_limit = [-65535.0] * 15, + is_connect=False, + invert_direction=False + ), + ] + ) \ No newline at end of file