From cdd063e9379f5e9f8f0aa1a49fa54291d9e1e51d Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Wed, 20 May 2026 00:20:10 +0800 Subject: [PATCH 01/13] =?UTF-8?q?feat:=20=E6=B7=BB=E5=8A=A0=207=20?= =?UTF-8?q?=E4=B8=AA=E8=AE=BE=E5=A4=87=E9=A9=B1=E5=8A=A8=E5=B9=B6=E8=BF=81?= =?UTF-8?q?=E7=A7=BB=E5=88=B0=E8=A3=85=E9=A5=B0=E5=99=A8=E6=B3=A8=E5=86=8C?= =?UTF-8?q?=E7=B3=BB=E7=BB=9F?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - 从 CosLab-SHU-DeviceTemplate 引入 7 个设备驱动 - 所有设备迁移到 @device/@action/@not_action 装饰器 - 完善 hk_a0 的 Modbus RTU 实现 - 设备列表:longer_bt100, hk_a0, dhjf_circulation_bath, duco_gcr5, xyz_guangdian, jyhsm_temperature_transmitter, runze_sy03b_t08 --- .../dhjf_circulation_bath.py | 479 ++++++++++++ .../dhjf_circulation_bath.yaml | 43 ++ .../graph_dhjf_circulation_bath.json | 16 + .../devices/duco_gcr5/duco_gcr5.py | 484 ++++++++++++ .../devices/duco_gcr5/duco_gcr5.yaml | 405 ++++++++++ .../duco_gcr5/graph_example_duco_gcr5.json | 20 + .../devices/hk_a0/graph_hk_a0.json | 22 + device_package_example/devices/hk_a0/hk_a0.py | 220 ++++++ .../devices/hk_a0/hk_a0.yaml | 137 ++++ ...example_jyhsm_temperature_transmitter.json | 28 + .../jyhsm_temperature_transmitter.py | 666 ++++++++++++++++ .../jyhsm_temperature_transmitter.yaml | 76 ++ .../longer_bt100/graph_longer_bt100.json | 20 + .../devices/longer_bt100/longer_bt100.py | 607 +++++++++++++++ .../devices/longer_bt100/longer_bt100.yaml | 299 ++++++++ .../graph_runze_sy03b_t08.json | 30 + .../runze_sy03b_t08/runze_sy03b_t08.py | 404 ++++++++++ .../runze_sy03b_t08/runze_sy03b_t08.yaml | 23 + .../graph_example_xyz_guangdian.json | 37 + .../devices/xyz_guangdian/xyz_guangdian.py | 711 ++++++++++++++++++ .../devices/xyz_guangdian/xyz_guangdian.yaml | 542 +++++++++++++ 21 files changed, 5269 insertions(+) create mode 100644 device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.py create mode 100644 device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.yaml create mode 100644 device_package_example/devices/dhjf_circulation_bath/graph_dhjf_circulation_bath.json create mode 100644 device_package_example/devices/duco_gcr5/duco_gcr5.py create mode 100644 device_package_example/devices/duco_gcr5/duco_gcr5.yaml create mode 100644 device_package_example/devices/duco_gcr5/graph_example_duco_gcr5.json create mode 100644 device_package_example/devices/hk_a0/graph_hk_a0.json create mode 100644 device_package_example/devices/hk_a0/hk_a0.py create mode 100644 device_package_example/devices/hk_a0/hk_a0.yaml create mode 100644 device_package_example/devices/jyhsm_temperature_transmitter/graph_example_jyhsm_temperature_transmitter.json create mode 100644 device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py create mode 100644 device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml create mode 100644 device_package_example/devices/longer_bt100/graph_longer_bt100.json create mode 100644 device_package_example/devices/longer_bt100/longer_bt100.py create mode 100644 device_package_example/devices/longer_bt100/longer_bt100.yaml create mode 100644 device_package_example/devices/runze_sy03b_t08/graph_runze_sy03b_t08.json create mode 100644 device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py create mode 100644 device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.yaml create mode 100644 device_package_example/devices/xyz_guangdian/graph_example_xyz_guangdian.json create mode 100644 device_package_example/devices/xyz_guangdian/xyz_guangdian.py create mode 100644 device_package_example/devices/xyz_guangdian/xyz_guangdian.yaml diff --git a/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.py b/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.py new file mode 100644 index 0000000..ac7c09a --- /dev/null +++ b/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.py @@ -0,0 +1,479 @@ +""" +DHJF-2005A 低温恒温搅拌反应浴驱动(Modbus RTU, RS485) +修正版本 - 支持 pymodbus 3.x (device_id 参数) + 正确的方法名 + 详细日志 + +与 Uni‑Lab‑OS temperature 接口对齐: +- 属性:status("Idle"/"Busy"), temp(°C), temp_target(°C), stir_speed(RPM), temp_warning(°C) +- 扩展属性:segment_count, current_segment, run_time_h, run_time_m, low_temp_alarm, over_temp_alarm +""" +import logging +import inspect +from typing import Dict, Any, List, Tuple + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +# 兼容不同版本 pymodbus 的导入 +try: + from pymodbus.client import ModbusSerialClient # 3.x +except Exception: + try: + from pymodbus.client.sync import ModbusSerialClient # 2.5.x + except Exception: + ModbusSerialClient = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="dhjf_circulation_bath", + category=["temperature"], + description="DHJF-2005A 低温恒温搅拌反应浴,支持多段程序控制", + display_name="DHJF 循环水浴" +) +class DHJFCirculationBath: + """ + DHJF-2005A 低温恒温搅拌反应浴驱动(Modbus RTU, RS485) + + UI 操作示例(在 Web 端动作面板中可以直接调用): + - set_temp(25.0) 或 set_temperature(25.0) + - set_segments(count=3) + - set_segment(index=1, temperature=5, hours=0, minutes=30) + - program(segments=[[5,0,30],[10,1,0],[3,0,10]]) + - start(), stop() + - start_stirring()/stop_stirring(), start_circulation()/stop_circulation() + - start_heating()/stop_heating(), start_cooling()/stop_cooling() + + 温度整数以×100写入(两位小数),例如 25.00°C -> 2500。 + """ + + _ros_node: "BaseROS2DeviceNode" + + # --- 寄存器映射(说明书通参表) --- + REG_MACHINE_TYPE = 0x0000 + REG_SEGMENT_COUNT = 0x0001 + REG_CURRENT_SEGMENT = 0x0002 + REG_MEASURED_TEMP = 0x0003 + REG_DISPLAY_TEMP = 0x0004 + REG_RUN_TIME_H = 0x0005 + REG_RUN_TIME_M = 0x0006 + + REG_SEG = { + 1: (0x0007, 0x0008, 0x0009), # 温度、小时、分钟 + 2: (0x000A, 0x000B, 0x000C), + 3: (0x000D, 0x000E, 0x000F), + 4: (0x0010, 0x0011, 0x0012), + 5: (0x0013, 0x0014, 0x0015), + } + + REG_CTRL = 0x0016 + BIT_POWER_KEY = 15 + BIT_RUN = 14 + BIT_STIRRING = 13 + BIT_CIRCULATION = 12 + BIT_COOL_OUT = 11 # R(只读输出状态) + BIT_HEAT_OUT = 10 # R + BIT_COOL_KEY = 9 + BIT_HEAT_KEY = 8 + + REG_ALARM = 0x0017 + BIT_RUN_RESULT = 12 + BIT_RUN_STATE = 11 + BIT_LOW_ALARM = 10 + BIT_OVER_ALARM = 9 + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and 'id' in kwargs: + device_id = kwargs.pop('id') + if config is None and 'config' in kwargs: + config = kwargs.pop('config') + self.device_id = device_id or "dhjf_circulation_bath" + self.config = config or {} + self.logger = logging.getLogger(f"DHJFCirculationBath.{self.device_id}") + self.logger.setLevel(logging.DEBUG) # 启用详细日志 + + self.port = self.config.get('port', 'COM4') + self.slave_id = int(self.config.get('slave_id', 1)) + self.baudrate = int(self.config.get('baudrate', 9600)) + self.timeout = float(self.config.get('timeout', 1.0)) + + self.client = None + self._connected = False # 添加连接状态标志 + + # 预填充所有属性(硬约束3) + self.data = { + "status": "Idle", + "temp": 0.0, + "temp_target": 0.0, + "stir_speed": 0.0, + "temp_warning": 0.0, + "segment_count": 1, + "current_segment": 1, + "run_time_h": 0, + "run_time_m": 0, + "low_temp_alarm": False, + "over_temp_alarm": False, + } + + self.logger.info(f"[INIT] DHJF-2005A 初始化: port={self.port}, slave_id={self.slave_id}, baudrate={self.baudrate}") + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + self.logger.info(f"[POST_INIT] ROS node 已设置") + + # --- 兼容 2.5/3.x 的读写封装 --- + def _detect_param_name(self, func) -> str: + """检测 pymodbus 版本对应的参数名""" + sig = inspect.signature(func) + params = list(sig.parameters.keys()) + self.logger.debug(f"[DETECT] 函数 {func.__name__} 参数: {params}") + + if "device_id" in params: + return "device_id" + elif "slave" in params: + return "slave" + elif "unit" in params: + return "unit" + else: + self.logger.warning(f"[DETECT] 未找到已知参数名,将尝试无参数调用") + return None + + def _connect(self) -> bool: + """建立 Modbus 连接""" + if self._connected and self.client: + return True + + if ModbusSerialClient is None: + self.logger.error("[CONNECT] 缺少 pymodbus,请安装: pip install pymodbus pyserial") + return False + + self.logger.info(f"[CONNECT] 正在连接串口 {self.port}...") + self.client = ModbusSerialClient( + port=self.port, baudrate=self.baudrate, + bytesize=8, parity='N', stopbits=1, timeout=self.timeout + ) + ok = bool(self.client.connect()) + if not ok: + self.logger.error(f"[CONNECT] 串口连接失败: {self.port}") + self.client = None + self._connected = False + return False + + self.logger.info(f"[CONNECT] 串口连接成功: {self.port}") + self._connected = True + return True + + def _disconnect(self): + if self.client: + self.client.close() + self.client = None + self._connected = False + self.logger.info("[DISCONNECT] 串口已关闭") + + def _read_regs(self, addr: int, count: int = 1): + """读取寄存器 - 兼容 pymodbus 2.x/3.x""" + if not self._connect(): + self.logger.error(f"[READ] 无法连接串口,读取 0x{addr:04X} 失败") + return None + + fn = self.client.read_holding_registers + param_name = self._detect_param_name(fn) + + kw = {"address": addr, "count": count} + if param_name: + kw[param_name] = self.slave_id + + self.logger.debug(f"[READ] 调用 read_holding_registers: {kw}") + + try: + res = fn(**kw) + if hasattr(res, "isError") and res.isError(): + self.logger.error(f"[READ] 读取失败: 0x{addr:04X}, 错误: {res}") + return None + regs = getattr(res, "registers", None) + if regs: + self.logger.info(f"[READ] 读取成功: 0x{addr:04X} = {regs}") + return regs + except Exception as e: + self.logger.error(f"[READ] 读取异常: 0x{addr:04X}, {e}") + return None + + def _write_reg(self, addr: int, value: int) -> bool: + """写入寄存器 - 兼容 pymodbus 2.x/3.x""" + if not self._connect(): + self.logger.error(f"[WRITE] 无法连接串口,写入 0x{addr:04X} 失败") + return False + + fn = self.client.write_register + param_name = self._detect_param_name(fn) + + val = int(value) & 0xFFFF + kw = {"address": addr, "value": val} + if param_name: + kw[param_name] = self.slave_id + + self.logger.debug(f"[WRITE] 调用 write_register: {kw}") + + try: + res = fn(**kw) + if hasattr(res, "isError") and res.isError(): + self.logger.error(f"[WRITE] 写入失败: 0x{addr:04X}={val}, 错误: {res}") + return False + self.logger.info(f"[WRITE] 写入成功: 0x{addr:04X}={val}") + return True + except Exception as e: + self.logger.error(f"[WRITE] 写入异常: 0x{addr:04X}={val}, {e}") + return False + + def _set_bit(self, addr: int, bit: int, enable: bool) -> bool: + """设置控制字的某个位""" + self.logger.info(f"[SET_BIT] 设置 0x{addr:04X} Bit{bit} = {enable}") + + regs = self._read_regs(addr, 1) + if not regs: + self.logger.error(f"[SET_BIT] 无法读取当前值,设置失败") + return False + + cur = regs[0] & 0xFFFF + self.logger.debug(f"[SET_BIT] 当前值: 0x{cur:04X} ({cur})") + + new_val = (cur | (1 << bit)) if enable else (cur & ~(1 << bit)) + self.logger.debug(f"[SET_BIT] 新值: 0x{new_val:04X} ({new_val})") + + ok = self._write_reg(addr, new_val) + if ok: + # 验证写入结果 + verify = self._read_regs(addr, 1) + if verify: + self.logger.info(f"[SET_BIT] 验证结果: 0x{verify[0]:04X}") + return ok + + async def _pulse_bit(self, addr: int, bit: int, pulse_sec: float = 0.1) -> bool: + """按键位脉冲触发:置位→短等待→清零。""" + ok = self._set_bit(addr, bit, True) + if not ok: + return False + if getattr(self, "_ros_node", None): + await self._ros_node.sleep(max(pulse_sec, 0.05)) + return self._set_bit(addr, bit, False) + + def _refresh(self): + t = self._read_regs(self.REG_MEASURED_TEMP, 1) + if t: + self.data["temp"] = t[0] * 0.01 + s1t = self._read_regs(self.REG_SEG[1][0], 1) + if s1t: + self.data["temp_target"] = s1t[0] * 0.01 + sc = self._read_regs(self.REG_SEGMENT_COUNT, 1) + if sc: + self.data["segment_count"] = sc[0] + cs = self._read_regs(self.REG_CURRENT_SEGMENT, 1) + if cs: + self.data["current_segment"] = cs[0] + hh = self._read_regs(self.REG_RUN_TIME_H, 1) + if hh: + self.data["run_time_h"] = hh[0] + mm = self._read_regs(self.REG_RUN_TIME_M, 1) + if mm: + self.data["run_time_m"] = mm[0] + al = self._read_regs(self.REG_ALARM, 1) + if al: + v = al[0] + self.data["low_temp_alarm"] = bool((v >> self.BIT_LOW_ALARM) & 1) + self.data["over_temp_alarm"] = bool((v >> self.BIT_OVER_ALARM) & 1) + + # --- 生命周期 --- + @action(description="初始化设备") + async def initialize(self) -> bool: + self.logger.info("[INITIALIZE] 开始初始化设备...") + self.data["status"] = "Busy" + if not self._connect(): + self.logger.error("[INITIALIZE] 连接失败") + self.data["status"] = "Idle" + return False + self._refresh() + self.data["status"] = "Idle" + self.logger.info("[INITIALIZE] 初始化完成") + return True + + @action(description="清理资源") + async def cleanup(self) -> bool: + self._disconnect() + self.data["status"] = "Idle" + return True + + # --- 属性(对齐 temperature 接口) --- + @property + def status(self) -> str: + return self.data.get("status", "Idle") + + @property + def temp(self) -> float: + return self.data.get("temp", 0.0) + + @property + def temp_target(self) -> float: + return self.data.get("temp_target", 0.0) + + @property + def stir_speed(self) -> float: + return self.data.get("stir_speed", 0.0) + + @property + def temp_warning(self) -> float: + return self.data.get("temp_warning", 0.0) + + # --- 基本动作 --- + async def set_temp(self, temp: float) -> bool: + """设置第1段设定温度。示例:set_temp(25.0) + Args: + temp: 目标温度(°C) + """ + self.logger.info(f"[SET_TEMP] 设置温度: {temp}°C") + result = await self.set_temperature(temp) + self.logger.info(f"[SET_TEMP] 结果: {result}") + return result + + async def set_temperature(self, temperature: float) -> bool: + """设置第1段设定温度(对齐 temperature 接口)。示例:set_temperature(25.0) + """ + val = int(round(temperature * 100)) & 0xFFFF + addr = self.REG_SEG[1][0] # 0x0007 + self.logger.info(f"[SET_TEMPERATURE] 写入寄存器 0x{addr:04X} = {val} (温度 {temperature}°C)") + ok = self._write_reg(addr, val) + if ok: + self.data["temp_target"] = float(temperature) + # 验证写入 + verify = self._read_regs(addr, 1) + if verify: + actual = verify[0] * 0.01 + self.logger.info(f"[SET_TEMPERATURE] 验证读回: {actual}°C (原始值 {verify[0]})") + return ok + + async def start(self) -> bool: + """开始程序运行。示例:start() + """ + self.data["status"] = "Busy" + ok = self._set_bit(self.REG_CTRL, self.BIT_RUN, True) + self.data["status"] = "Idle" + return ok + + async def stop(self) -> bool: + """停止程序运行。示例:stop() + """ + self.data["status"] = "Busy" + ok = self._set_bit(self.REG_CTRL, self.BIT_RUN, False) + self.data["status"] = "Idle" + return ok + + async def start_stirring(self) -> bool: + """开启搅拌。示例:start_stirring() + """ + return self._set_bit(self.REG_CTRL, self.BIT_STIRRING, True) + + async def stop_stirring(self) -> bool: + """关闭搅拌。示例:stop_stirring() + """ + return self._set_bit(self.REG_CTRL, self.BIT_STIRRING, False) + + async def start_circulation(self) -> bool: + """开启循环。示例:start_circulation() + """ + self.logger.info("[START_CIRCULATION] 开启循环") + result = self._set_bit(self.REG_CTRL, self.BIT_CIRCULATION, True) + self.logger.info(f"[START_CIRCULATION] 结果: {result}") + return result + + async def stop_circulation(self) -> bool: + """关闭循环。示例:stop_circulation() + """ + self.logger.info("[STOP_CIRCULATION] 关闭循环") + result = self._set_bit(self.REG_CTRL, self.BIT_CIRCULATION, False) + self.logger.info(f"[STOP_CIRCULATION] 结果: {result}") + return result + + async def start_heating(self) -> bool: + """按下加热键(按键脉冲)。示例:start_heating() + """ + return await self._pulse_bit(self.REG_CTRL, self.BIT_HEAT_KEY, 0.1) + + async def stop_heating(self) -> bool: + """松开加热键。示例:stop_heating() + """ + return await self._pulse_bit(self.REG_CTRL, self.BIT_HEAT_KEY, 0.1) + + async def start_cooling(self) -> bool: + """按下制冷键(按键脉冲)。示例:start_cooling() + """ + return await self._pulse_bit(self.REG_CTRL, self.BIT_COOL_KEY, 0.1) + + async def stop_cooling(self) -> bool: + """松开制冷键。示例:stop_cooling() + """ + return await self._pulse_bit(self.REG_CTRL, self.BIT_COOL_KEY, 0.1) + + async def power_on(self) -> bool: + """按电源键(按键脉冲)。示例:power_on() + """ + return await self._pulse_bit(self.REG_CTRL, self.BIT_POWER_KEY, 0.1) + + async def power_off(self) -> bool: + """按电源键关闭(按键脉冲)。示例:power_off() + """ + return await self._pulse_bit(self.REG_CTRL, self.BIT_POWER_KEY, 0.1) + + # --- 多段程序动作 --- + async def set_segments(self, count: int) -> bool: + """设置程序段数(1~5)。示例:set_segments(3) + """ + if count < 1 or count > 5: + return False + ok = self._write_reg(self.REG_SEGMENT_COUNT, int(count)) + if ok: + self.data["segment_count"] = int(count) + return ok + + async def set_segment(self, index: int, temperature: float, hours: int, minutes: int) -> bool: + """设置指定段的温度与时长。示例:set_segment(2, 10.0, 1, 0) + """ + if index not in self.REG_SEG or hours < 0 or minutes < 0 or minutes > 59: + return False + reg_t, reg_h, reg_m = self.REG_SEG[index] + ok = True + ok &= self._write_reg(reg_t, int(round(temperature * 100)) & 0xFFFF) + ok &= self._write_reg(reg_h, int(hours) & 0xFFFF) + ok &= self._write_reg(reg_m, int(minutes) & 0xFFFF) + if index == 1 and ok: + self.data["temp_target"] = float(temperature) + return ok + + async def program(self, segments: List[Tuple[float, int, int]]) -> bool: + """批量设置 1~5 段程序。示例:program([[5,0,30],[10,1,0],[3,0,10]]) + """ + n = len(segments) + if n < 1 or n > 5: + return False + ok = await self.set_segments(n) + for i, triplet in enumerate(segments, start=1): + t, h, m = float(triplet[0]), int(triplet[1]), int(triplet[2]) + ok &= await self.set_segment(i, t, h, m) + return ok \ No newline at end of file diff --git a/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.yaml b/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.yaml new file mode 100644 index 0000000..4790e70 --- /dev/null +++ b/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.yaml @@ -0,0 +1,43 @@ +dhjf_circulation_bath: + category: + - dhjf_circulation_bath + class: + action_value_mappings: {} + module: unilabos.devices.temperature.dhjf_circulation_bath:DHJFCirculationBath + status_types: {} + type: python + config_info: [] + description: '' + handles: [] + icon: '' + init_param_schema: {} + ui: + description: DHJF-2005A 恒温循环水浴(RS485/Modbus),支持多段程序。温度以°C表示,内部以×100写入寄存器。 + examples: + - call: + action: program + params: + segments: + - - 5 + - 0 + - 30 + - - 10 + - 1 + - 0 + - - 3 + - 0 + - 10 + title: 三段程序示例 + - call: + action: set_segment + params: + hours: 1 + index: 2 + minutes: 0 + temperature: 10 + title: 设置段数并单独设置第2段 + notes: + - start_heating/start_cooling 为面板按键的脉冲触发,加热/制冷输出位是只读反馈,由设备温控逻辑决定。 + - minutes 必须在 0~59;hours ≥ 0。 + - set_temperature 仅对应第1段设温,以便与 temperature 类设备接口对齐。 + version: 1.0.0 diff --git a/device_package_example/devices/dhjf_circulation_bath/graph_dhjf_circulation_bath.json b/device_package_example/devices/dhjf_circulation_bath/graph_dhjf_circulation_bath.json new file mode 100644 index 0000000..7272f1b --- /dev/null +++ b/device_package_example/devices/dhjf_circulation_bath/graph_dhjf_circulation_bath.json @@ -0,0 +1,16 @@ +{ + "nodes": [ + { + "id": "dhjf_bath_1", + "name": "DHJF-2005A 恒温循环水浴", + "children": [], + "parent": null, + "type": "device", + "class": "dhjf_circulation_bath", + "position": {"x": 0, "y": 0, "z": 0}, + "config": {"port": "COM4", "slave_id": 1, "baudrate": 9600, "timeout": 1.0}, + "data": {} + } + ], + "links": [] +} diff --git a/device_package_example/devices/duco_gcr5/duco_gcr5.py b/device_package_example/devices/duco_gcr5/duco_gcr5.py new file mode 100644 index 0000000..668acfd --- /dev/null +++ b/device_package_example/devices/duco_gcr5/duco_gcr5.py @@ -0,0 +1,484 @@ +""" +DUCO GCR5-910 协作机器人驱动(TCP 2000 端口纯文本协议) + +真实命令格式(通过 Telnet 验证): + - poweron() -> poweron success + - poweroff() -> poweroff success + - enable() -> enable success + - disable() -> disable success + - run("program/20260421.jspf",70) -> run success + - state -> 4:0:2:x (机器人状态:程序状态:操作模式:子状态) + - speed(50) -> set speed 50% + - clear() -> clear alarm + +状态解析: + state[0]: 0=Start 4=PowerOff 5=Disable 6=Enable + state[1]: 0=Stopped 2=Running 3=Paused + state[2]: 2=Remote 5=Local + state[3]: Local下 0=Manual 1=Auto +""" + +import logging +import socket +import struct +import threading +import time as time_module +from typing import Dict, Any, List, Optional + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="duco_gcr5", + category=["robot"], + description="DUCO GCR5-910 协作机器人,TCP 通信", + display_name="DUCO 协作机器人" +) +class DucoGCR5: + """新松 DUCO GCR5-910 协作机器人驱动(TCP 2000 文本协议版)""" + + _ros_node: "BaseROS2DeviceNode" + + ROBOT_STATE_MAP = { + 0: "SR_Start", + 1: "SR_Initialize", + 2: "SR_Logout", + 3: "SR_Login", + 4: "SR_PowerOff", + 5: "SR_Disable", + 6: "SR_Enable", + } + + PROGRAM_STATE_MAP = { + 0: "SP_Stopped", + 1: "SP_Stopping", + 2: "SP_Running", + 3: "SP_Paused", + 4: "SP_Pausing", + 5: "SP_TaskRunning", + } + + STATUS_MAP = { + "SP_Stopped": "Idle", + "SP_Stopping": "Busy", + "SP_Running": "Running", + "SP_Paused": "Paused", + "SP_Pausing": "Busy", + "SP_TaskRunning": "Running", + } + + OP_MODE_MAP = { + 2: "Remote", + 5: "Local", + } + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and "id" in kwargs: + device_id = kwargs.pop("id") + if config is None and "config" in kwargs: + config = kwargs.pop("config") + self.device_id = device_id or "duco_gcr5" + self.config = config or {} + self.logger = logging.getLogger(f"DucoGCR5.{self.device_id}") + + # 连接参数 + self._ip = self.config.get("ip", "192.168.1.10") + self._cmd_port = self.config.get("cmd_port", 2000) # 命令端口 + self._status_port = self.config.get("status_port", 2001) # 状态推送端口 + self._timeout = self.config.get("timeout", 5.0) + + # Socket + self._cmd_socket: Optional[socket.socket] = None + self._status_socket: Optional[socket.socket] = None + + # 状态监听 + self._status_thread: Optional[threading.Thread] = None + self._running = False + + # 预填充 + self.data = { + "status": "Offline", + "position": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], + "tcp_pose": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], + "robot_state_name": "SR_Start", + "program_state_name": "SP_Stopped", + "speed": 100.0, + "joint_velocity": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], + "joint_torque": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], + "tcp_force": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0], + "operation_mode_name": "Unknown", + "error_message": "", + } + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + # ======================== TCP 命令通信 ======================== + + def _connect_cmd(self) -> bool: + """连接 TCP 2000 命令端口""" + try: + if self._cmd_socket: + try: + self._cmd_socket.close() + except Exception: + pass + self._cmd_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + self._cmd_socket.settimeout(self._timeout) + self._cmd_socket.connect((self._ip, self._cmd_port)) + self.logger.info(f"命令端口 {self._ip}:{self._cmd_port} 连接成功") + return True + except Exception as e: + self.logger.error(f"命令端口连接失败: {e}") + self._cmd_socket = None + return False + + def _send_cmd(self, cmd: str) -> Optional[str]: + """发送命令并接收响应""" + if not self._cmd_socket: + if not self._connect_cmd(): + return None + try: + self._cmd_socket.sendall(cmd.encode("utf-8")) + response = self._cmd_socket.recv(4096).decode("utf-8", errors="ignore").strip() + self.logger.debug(f"CMD: {cmd} -> {response}") + return response + except socket.timeout: + self.logger.warning(f"命令超时: {cmd}") + return None + except Exception as e: + self.logger.error(f"命令发送失败: {e}") + try: + if self._cmd_socket: + self._cmd_socket.close() + except Exception: + pass + self._cmd_socket = None + return None + + def _is_success(self, resp: Optional[str]) -> bool: + """判断响应是否成功""" + if resp is None: + return False + low = resp.lower() + return "success" in low or "ok" in low + + # ======================== TCP 状态端口 ======================== + + def _connect_status(self) -> bool: + """连接 TCP 2001 状态推送端口""" + try: + if self._status_socket: + try: + self._status_socket.close() + except Exception: + pass + self._status_socket = socket.socket(socket.AF_INET, socket.SOCK_STREAM) + self._status_socket.settimeout(2.0) + self._status_socket.connect((self._ip, self._status_port)) + self.logger.info(f"状态端口 {self._ip}:{self._status_port} 连接成功") + return True + except Exception as e: + self.logger.error(f"状态端口连接失败: {e}") + self._status_socket = None + return False + + def _parse_status_packet(self, data: bytes): + """解析状态包""" + if len(data) < 1468: + return + try: + joint_pos = struct.unpack_from("<7f", data, 0)[:6] + joint_vel = struct.unpack_from("<7f", data, 28)[:6] + joint_torque = struct.unpack_from("<7f", data, 84)[:6] + tcp_pose = struct.unpack_from("<6f", data, 368) + tcp_force = struct.unpack_from("<6f", data, 440) + global_speed = struct.unpack_from("= 1468: + packet = buffer[:1468] + buffer = buffer[1468:] + self._parse_status_packet(packet) + except socket.timeout: + continue + except Exception as e: + if self._running: + self.logger.error(f"状态监听异常: {e}") + break + if self._running: + self.data["status"] = "Offline" + self.logger.info("状态监听线程退出") + + # ======================== 生命周期 ======================== + + @action(description="初始化设备") + async def initialize(self) -> bool: + """初始化""" + if not self._connect_cmd(): + self.data["status"] = "Offline" + return False + + if not self._connect_status(): + self.logger.warning("状态端口连接失败,将继续但无法接收实时状态") + + self._running = True + self._status_thread = threading.Thread( + target=self._status_listener, daemon=True, name=f"duco_status_{self.device_id}" + ) + self._status_thread.start() + + await self._ros_node.sleep(0.5) + + # 查询初始状态 + state = self._query_state_raw() + if state: + self.logger.info(f"初始 state={state}") + if state[0] == 6: + self.logger.info("✅ 机器人已使能") + elif state[0] == 4: + self.logger.info("⚠️ 机器人处于 PowerOff 状态,需要 poweron()") + elif state[0] == 5: + self.logger.info("⚠️ 机器人处于 Disable 状态,需要 enable()") + + self.logger.info("DUCO GCR5(TCP 2000)初始化完成") + return True + + @action(description="清理资源") + async def cleanup(self) -> bool: + """清理""" + self._running = False + if self._status_thread and self._status_thread.is_alive(): + self._status_thread.join(timeout=3.0) + if self._cmd_socket: + try: + self._cmd_socket.close() + except Exception: + pass + self._cmd_socket = None + if self._status_socket: + try: + self._status_socket.close() + except Exception: + pass + self._status_socket = None + self.data["status"] = "Offline" + return True + + def _query_state_raw(self) -> Optional[List[int]]: + """查询 state,返回 [机器人状态, 程序状态, 操作模式, 子状态]""" + resp = self._send_cmd("state") + if not resp: + return None + try: + return [int(x) for x in resp.split(":")] + except Exception: + self.logger.warning(f"state 响应解析失败: {resp}") + return None + + # ======================== 属性 ======================== + + @property + def status(self) -> str: + return self.data.get("status", "Offline") + + @property + def position(self) -> List[float]: + return self.data.get("position", [0.0] * 6) + + @property + def tcp_pose(self) -> List[float]: + return self.data.get("tcp_pose", [0.0] * 6) + + @property + def joint_velocity(self) -> List[float]: + return self.data.get("joint_velocity", [0.0] * 6) + + @property + def joint_torque(self) -> List[float]: + return self.data.get("joint_torque", [0.0] * 6) + + @property + def tcp_force(self) -> List[float]: + return self.data.get("tcp_force", [0.0] * 6) + + @property + def speed(self) -> float: + return self.data.get("speed", 100.0) + + @property + def robot_state_name(self) -> str: + return self.data.get("robot_state_name", "SR_Start") + + @property + def program_state_name(self) -> str: + return self.data.get("program_state_name", "SP_Stopped") + + @property + def operation_mode_name(self) -> str: + return self.data.get("operation_mode_name", "Unknown") + + @property + def error_message(self) -> str: + return self.data.get("error_message", "") + + # ======================== 动作(基于 Telnet 验证格式) ======================== + + async def power_on(self) -> str: + """上电""" + resp = self._send_cmd("poweron()") + if self._is_success(resp): + return "poweron success" + else: + return f"poweron fail: {resp or 'no response'}" + + async def power_off(self) -> str: + """下电""" + resp = self._send_cmd("poweroff()") + if self._is_success(resp): + return "poweroff success" + else: + return f"poweroff fail: {resp or 'no response'}" + + async def enable(self) -> str: + """使能""" + resp = self._send_cmd("enable()") + if self._is_success(resp): + return "enable success" + else: + return f"enable fail: {resp or 'no response'}" + + async def disable(self) -> str: + """去使能""" + resp = self._send_cmd("disable()") + if self._is_success(resp): + return "disable success" + else: + return f"disable fail: {resp or 'no response'}" + + async def run_program(self, name: str, speed: float = 0.0) -> str: + """ + 运行示教器工程 + Args: + name: 工程名称(支持两种格式) + - 简短名: "20260421" → 自动补全为 "program/20260421.jspf" + - 完整路径: "program/xxx.jspf" + speed: 速度百分比 (1-100),传 0 使用默认速度 70 + """ + # 自动补全路径 + if not name.startswith("program/"): + name = f"program/{name}.jspf" + + speed_val = int(speed) if speed > 0 else 70 + cmd = f'run("{name}",{speed_val})' + resp = self._send_cmd(cmd) + if self._is_success(resp): + return "run success" + else: + return f"run fail: {resp or 'no response'}" + + async def pause(self) -> str: + """暂停当前工程(需确认真实命令)""" + resp = self._send_cmd("pause()") + if self._is_success(resp): + return "pause success" + else: + return f"pause fail: {resp or 'no response'}" + + async def resume(self) -> str: + """恢复暂停的工程(需确认真实命令)""" + resp = self._send_cmd("resume()") + if self._is_success(resp): + return "resume success" + else: + return f"resume fail: {resp or 'no response'}" + + async def stop(self) -> str: + """停止当前工程(需确认真实命令)""" + resp = self._send_cmd("stop()") + if self._is_success(resp): + return "stop success" + else: + return f"stop fail: {resp or 'no response'}" + + async def set_speed(self, speed: float) -> str: + """设置全局速度百分比""" + spd = int(max(1, min(100, float(speed)))) + resp = self._send_cmd(f"speed({spd})") + if self._is_success(resp): + self.data["speed"] = float(spd) + return f"speed {spd} success" + else: + return f"speed fail: {resp or 'no response'}" + + async def query_state(self) -> str: + """查询机器人状态(返回原始字符串)""" + return self._send_cmd("state") or "state query fail" + + async def clear_error(self) -> str: + """清除告警""" + resp = self._send_cmd("clear()") + if self._is_success(resp): + self.data["error_message"] = "" + return "clear success" + else: + return f"clear fail: {resp or 'no response'}" \ No newline at end of file diff --git a/device_package_example/devices/duco_gcr5/duco_gcr5.yaml b/device_package_example/devices/duco_gcr5/duco_gcr5.yaml new file mode 100644 index 0000000..da63683 --- /dev/null +++ b/device_package_example/devices/duco_gcr5/duco_gcr5.yaml @@ -0,0 +1,405 @@ +duco_gcr5: + action_value_mappings: {} + category: + - robot_arm + - duco_gcr5 + class: + action_value_mappings: + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-clear_error: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: clear_error参数 + type: object + type: UniLabJsonCommandAsync + auto-disable: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: disable参数 + type: object + type: UniLabJsonCommandAsync + auto-enable: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: enable参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-pause: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: pause参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-power_off: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: power_off参数 + type: object + type: UniLabJsonCommandAsync + auto-power_on: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: power_on参数 + type: object + type: UniLabJsonCommandAsync + auto-query_state: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: query_state参数 + type: object + type: UniLabJsonCommandAsync + auto-resume: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: resume参数 + type: object + type: UniLabJsonCommandAsync + auto-run_program: + feedback: {} + goal: {} + goal_default: + name: null + speed: 0.0 + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + name: + type: string + speed: + default: 0.0 + type: number + required: + - name + type: object + result: {} + required: + - goal + title: run_program参数 + type: object + type: UniLabJsonCommandAsync + auto-set_speed: + feedback: {} + goal: {} + goal_default: + speed: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + speed: + type: number + required: + - speed + type: object + result: {} + required: + - goal + title: set_speed参数 + type: object + type: UniLabJsonCommandAsync + auto-stop: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: stop参数 + type: object + type: UniLabJsonCommandAsync + module: unilabos.devices.robot_arm.duco_gcr5:DucoGCR5 + status_types: + error_message: str + joint_torque: String + joint_velocity: String + operation_mode_name: str + position: String + program_state_name: str + robot_state_name: str + speed: float + status: str + tcp_force: String + tcp_pose: String + type: python + config_info: [] + description: 新松 DUCO GCR5-910 协作机器人(TCP 2000 端口文本协议) + handles: [] + icon: '' + id: duco_gcr5 + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + error_message: + type: string + joint_torque: + items: + type: number + type: array + joint_velocity: + items: + type: number + type: array + operation_mode_name: + type: string + position: + items: + type: number + type: array + program_state_name: + type: string + robot_state_name: + type: string + speed: + type: number + status: + type: string + tcp_force: + items: + type: number + type: array + tcp_pose: + items: + type: number + type: array + required: + - status + - position + - tcp_pose + - joint_velocity + - joint_torque + - tcp_force + - speed + - robot_state_name + - program_state_name + - operation_mode_name + - error_message + type: object + status_types: + error_message: str + joint_torque: list + joint_velocity: list + operation_mode_name: str + position: list + program_state_name: str + robot_state_name: str + speed: float + status: str + tcp_force: list + tcp_pose: list + version: 1.0.0 diff --git a/device_package_example/devices/duco_gcr5/graph_example_duco_gcr5.json b/device_package_example/devices/duco_gcr5/graph_example_duco_gcr5.json new file mode 100644 index 0000000..a1487ce --- /dev/null +++ b/device_package_example/devices/duco_gcr5/graph_example_duco_gcr5.json @@ -0,0 +1,20 @@ +{ + "nodes": [ + { + "id": "duco_gcr5_1", + "name": "新松GCR5机械臂", + "children": [], + "parent": null, + "type": "device", + "class": "duco_gcr5", + "position": {"x": 500, "y": 500, "z": 0}, + "config": { + "ip": "192.168.1.10", + "cmd_port": 2000, + "status_port": 2001, + "timeout": 5.0 + }, + "data": {} + } + ] +} \ No newline at end of file diff --git a/device_package_example/devices/hk_a0/graph_hk_a0.json b/device_package_example/devices/hk_a0/graph_hk_a0.json new file mode 100644 index 0000000..c0c77dd --- /dev/null +++ b/device_package_example/devices/hk_a0/graph_hk_a0.json @@ -0,0 +1,22 @@ +{ + "nodes": [ + { + "id": "hk_a0_module_1", + "name": "华控模拟量输出", + "children": [], + "parent": null, + "type": "device", + "class": "hk_a0", + "position": { + "x": 400, + "y": 300, + "z": 0 + }, + "config": { + "slave_address": 1 + }, + "data": {} + } + ], + "links": [] +} diff --git a/device_package_example/devices/hk_a0/hk_a0.py b/device_package_example/devices/hk_a0/hk_a0.py new file mode 100644 index 0000000..95fa431 --- /dev/null +++ b/device_package_example/devices/hk_a0/hk_a0.py @@ -0,0 +1,220 @@ +import logging +from typing import Dict, Any, List, Optional + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +# 兼容不同版本 pymodbus +try: + from pymodbus.client import ModbusSerialClient # 3.x +except Exception: + try: + from pymodbus.client.sync import ModbusSerialClient # 2.5.x + except Exception: + ModbusSerialClient = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="hk_a0", + category=["io_module"], + description="HK-A0 模拟输出模块,6通道,Modbus RTU", + display_name="HK-A0 输出模块" +) +class HKA0: + """ + Huaikong Electronic HK-A0 Analog Output Module Driver (RS485 Modbus RTU) + Supports 6 output channels (AO1-AO6), 12-bit resolution. + Value scaling: Physical Value * 1000 = Register Value. + """ + _ros_node: "BaseROS2DeviceNode" + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and 'id' in kwargs: + device_id = kwargs.pop('id') + if config is None and 'config' in kwargs: + config = kwargs.pop('config') + + self.device_id = device_id or "hk_a0_module_1" + self.config = config or {} + + # 日志配置 + self.logger = logging.getLogger(f"HKA0.{self.device_id}") + + # Modbus 连接参数 + self.port = self.config.get("port", "/dev/ttyUSB0") + self.baudrate = self.config.get("baudrate", 9600) + self.slave_address = self.config.get("slave_address", 1) + self.channel_count = self.config.get("channel_count", 6) + self.timeout = self.config.get("timeout", 1.0) + + # Modbus 客户端 + self.client: Optional[ModbusSerialClient] = None + + # 寄存器地址映射 (根据 HK-A0 手册) + self.REG_OUTPUT_BASE = 0x0009 # 输出寄存器起始地址 + + # Pre-fill self.data + self.data = { + "status": "Idle", + "outputs": [0.0] * self.channel_count, + "last_error": "" + } + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + @action(description="初始化设备") + async def initialize(self) -> bool: + """初始化 Modbus 连接""" + try: + if ModbusSerialClient is None: + self.logger.error("pymodbus not installed") + self.data["status"] = "Error" + self.data["last_error"] = "pymodbus not installed" + return False + + self.client = ModbusSerialClient( + port=self.port, + baudrate=self.baudrate, + timeout=self.timeout, + parity='N', + stopbits=1, + bytesize=8 + ) + + if not self.client.connect(): + self.logger.error(f"Failed to connect to {self.port}") + self.data["status"] = "Error" + self.data["last_error"] = "Connection failed" + return False + + self.data["status"] = "Idle" + self.logger.info(f"HK-A0 initialized at {self.port}, Slave Addr: {self.slave_address}") + return True + + except Exception as e: + self.logger.error(f"Initialization error: {e}") + self.data["status"] = "Error" + self.data["last_error"] = str(e) + return False + + @action(description="设置输出值") + async def set_output(self, channel: int, value: float) -> bool: + """ + 设置输出值 + + Args: + channel[通道号]: 通道编号 (1-6) + value[输出值]: 物理值 (0.0-5.0 V) + """ + if not (1 <= channel <= self.channel_count): + self.logger.error(f"Invalid channel: {channel}") + self.data["last_error"] = f"Invalid channel: {channel}" + return False + + if not (0.0 <= value <= 5.0): + self.logger.error(f"Value out of range: {value}V (must be 0.0-5.0)") + self.data["last_error"] = f"Value out of range: {value}V" + return False + + try: + # 缩放: 1.000V -> 1000 + raw_value = int(value * 1000) + reg_addr = self.REG_OUTPUT_BASE + channel + + # 写入单个保持寄存器 + result = self.client.write_register( + address=reg_addr, + value=raw_value, + slave=self.slave_address + ) + + if result.isError(): + self.logger.error(f"Modbus write error for Ch{channel}") + self.data["last_error"] = "Modbus write error" + return False + + self.data["outputs"][channel - 1] = value + self.logger.info(f"Set HK-A0 Ch{channel} to {value}V (Raw: {raw_value})") + return True + + except Exception as e: + self.logger.error(f"Error setting output: {e}") + self.data["last_error"] = str(e) + return False + + @action(description="停止所有输出") + async def stop_all(self) -> bool: + """停止所有通道输出(设置为 0V)""" + success = True + for i in range(1, self.channel_count + 1): + if not await self.set_output(i, 0.0): + success = False + return success + + @action(description="清理资源") + async def cleanup(self) -> bool: + """清理资源,关闭 Modbus 连接""" + try: + if self.client and self.client.is_socket_open(): + self.client.close() + self.data["status"] = "Offline" + self.logger.info("HK-A0 connection closed") + return True + except Exception as e: + self.logger.error(f"Cleanup error: {e}") + return False + + @action(description="读取所有输出值") + async def read_outputs(self) -> List[float]: + """读取所有通道的当前输出值""" + try: + result = self.client.read_holding_registers( + address=self.REG_OUTPUT_BASE + 1, + count=self.channel_count, + slave=self.slave_address + ) + + if result.isError(): + self.logger.error("Failed to read outputs") + return self.data["outputs"] + + # 转换为物理值 + outputs = [reg / 1000.0 for reg in result.registers] + self.data["outputs"] = outputs + return outputs + + except Exception as e: + self.logger.error(f"Error reading outputs: {e}") + return self.data["outputs"] + + @property + @topic_config() + def status(self) -> str: + return self.data.get("status", "Idle") + + @property + @topic_config() + def outputs(self) -> List[float]: + return self.data.get("outputs", [0.0]*self.channel_count) diff --git a/device_package_example/devices/hk_a0/hk_a0.yaml b/device_package_example/devices/hk_a0/hk_a0.yaml new file mode 100644 index 0000000..0bc2a25 --- /dev/null +++ b/device_package_example/devices/hk_a0/hk_a0.yaml @@ -0,0 +1,137 @@ +hk_a0: + category: + - hk_a0 + class: + action_value_mappings: + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-set_output: + feedback: {} + goal: {} + goal_default: + channel: null + value: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + channel: + type: integer + value: + type: number + required: + - channel + - value + type: object + result: {} + required: + - goal + title: set_output参数 + type: object + type: UniLabJsonCommandAsync + auto-stop_all: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: stop_all参数 + type: object + type: UniLabJsonCommandAsync + module: unilabos.devices.custom.hk_a0:HKA0 + status_types: + outputs: String + status: str + type: python + config: + baudrate: 9600 + channel_count: 6 + port: COM3 + slave_address: 1 + config_info: [] + description: '' + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + outputs: + items: + type: number + type: array + status: + type: string + required: + - status + - outputs + type: object + version: 1.0.0 diff --git a/device_package_example/devices/jyhsm_temperature_transmitter/graph_example_jyhsm_temperature_transmitter.json b/device_package_example/devices/jyhsm_temperature_transmitter/graph_example_jyhsm_temperature_transmitter.json new file mode 100644 index 0000000..7317199 --- /dev/null +++ b/device_package_example/devices/jyhsm_temperature_transmitter/graph_example_jyhsm_temperature_transmitter.json @@ -0,0 +1,28 @@ +{ + "nodes": [ + { + "id": "jyhsm_temp_1", + "name": "JYHSM一体化温度变送器", + "children": [], + "parent": null, + "type": "device", + "class": "jyhsm_temperature_transmitter", + "position": {"x": 0, "y": 0, "z": 0}, + "config": { + "port": "COM4", + "baudrate": 9600, + "slave_address": 1, + "timeout": 1.0 + }, + "data": { + "status": "Idle", + "temperature": 0.0, + "offset": 0.0, + "unit": "℃", + "slave_address": 1, + "baudrate": 9600 + } + } + ], + "links": [] +} \ No newline at end of file diff --git a/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py new file mode 100644 index 0000000..2d62150 --- /dev/null +++ b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py @@ -0,0 +1,666 @@ +""" +JYHSM 一体化温度变送器驱动 +厂家:安徽久跃仪表有限公司 +通信协议:Modbus RTU (RS485) +默认参数:9600, 8N1, 从站地址 1 +寄存器映射: + - 0x0000: 实时值*100 (有符号整型) + - 0x0001: 实时值*10 (有符号整型) + - 0x0002-0x0003: 浮点值 (ABCD格式, 32bit IEEE754) + - 0x0108-0x0109: 偏移值 (浮点, ABCD格式) + - 0x012C: 从站地址 + - 0x012D: 波特率 (0~7 对应 1200~115200) + - 0x012E: 校验位 (0=None, 1=Odd, 2=Even) + - 0x012F: 小数位数 (0~3) + - 0x0130: 单位 (11=℃, 12=℉) + - 0x0131: ADC速率 (10 或 40 Hz) + +新增功能: + - 温度阈值监控 + - 达到目标温度后触发提醒 +""" + +import logging +import struct +import time as time_module +import asyncio +from typing import Dict, Any, List + +try: + import serial +except ImportError: + serial = None + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +# ==================== Modbus RTU 工具函数 ==================== + +def _crc16_modbus(data: bytes) -> int: + """计算 Modbus RTU CRC16 校验码""" + crc = 0xFFFF + for byte in data: + crc ^= byte + for _ in range(8): + if crc & 0x0001: + crc = (crc >> 1) ^ 0xA001 + else: + crc >>= 1 + return crc + + +def _build_read_request(slave_addr: int, func_code: int, start_reg: int, reg_count: int) -> bytes: + """构建 Modbus RTU 读请求帧""" + frame = struct.pack(">BBH H", slave_addr, func_code, start_reg, reg_count) + crc = _crc16_modbus(frame) + frame += struct.pack(" bytes: + """构建 Modbus RTU 写单个寄存器请求帧 (06H)""" + frame = struct.pack(">BBH H", slave_addr, 0x06, reg_addr, value) + crc = _crc16_modbus(frame) + frame += struct.pack(" bytes: + """构建 Modbus RTU 写多个寄存器请求帧 (10H)""" + reg_count = len(values) + byte_count = reg_count * 2 + frame = struct.pack(">BBH HB", slave_addr, 0x10, start_reg, reg_count, byte_count) + for v in values: + frame += struct.pack(">H", v) + crc = _crc16_modbus(frame) + frame += struct.pack(" bytes: + """验证 Modbus RTU 响应帧""" + if resp is None or len(resp) < 5: + raise ValueError(f"响应帧过短或为空: {resp}") + + header = bytes([slave_addr, func_code]) + idx = resp.find(header) + if idx < 0: + err_header = bytes([slave_addr, func_code | 0x80]) + err_idx = resp.find(err_header) + if err_idx >= 0: + err_code = resp[err_idx + 2] if len(resp) > err_idx + 2 else 0xFF + raise ValueError(f"Modbus 异常响应, 功能码 {hex(func_code)}, 异常码 {hex(err_code)}") + raise ValueError(f"响应中未找到帧头 [{hex(slave_addr)}, {hex(func_code)}]: {resp.hex()}") + + frame = resp[idx:] + if len(frame) < 5: + raise ValueError(f"响应帧数据不完整: {frame.hex()}") + + if func_code in (0x03, 0x04): + byte_count = frame[2] + expected_len = 3 + byte_count + 2 + if len(frame) < expected_len: + raise ValueError(f"响应帧长度不足: 期望{expected_len}, 实际{len(frame)}") + payload = frame[:expected_len] + crc_received = struct.unpack(" float: + """将两个 16bit 寄存器值解码为 IEEE754 浮点数 (ABCD 大端格式)""" + raw = struct.pack(">HH", high_word, low_word) + return struct.unpack(">f", raw)[0] + + +def _encode_float_abcd(value: float) -> tuple: + """将浮点数编码为两个 16bit 寄存器值 (ABCD 大端格式)""" + raw = struct.pack(">f", value) + high_word, low_word = struct.unpack(">HH", raw) + return high_word, low_word + + +# ==================== 波特率映射 ==================== + +BAUDRATE_MAP = { + 0: 1200.0, + 1: 2400.0, + 2: 4800.0, + 3: 9600.0, + 4: 19200.0, + 5: 38400.0, + 6: 57600.0, + 7: 115200.0, +} +BAUDRATE_REVERSE_MAP = {v: k for k, v in BAUDRATE_MAP.items()} + +UNIT_MAP = { + 11.0: "℃", + 12.0: "℉", +} + + +# ==================== 设备驱动类 ==================== + +@device( + id="jyhsm_temperature_transmitter", + category=["temperature"], + description="JYHSM 一体化温度变送器,Modbus RTU", + display_name="JYHSM 温度变送器" +) +class JyhsmTemperatureTransmitter: + """ + JYHSM 一体化温度变送器 Modbus RTU 驱动 + (所有数值类型均对齐为 float 以支持 Uni-Lab-OS 框架) + + 新增功能: + - 温度阈值监控 + - 达到目标温度后触发提醒 + """ + + _ros_node: "BaseROS2DeviceNode" + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and "id" in kwargs: + device_id = kwargs.pop("id") + if config is None and "config" in kwargs: + config = kwargs.pop("config") + + self.device_id = device_id or "jyhsm_temp_1" + self.config = config or {} + self.logger = logging.getLogger(f"JyhsmTemp.{self.device_id}") + + # 串口配置 + self._port = self.config.get("port", "COM4") + self._baudrate = float(self.config.get("baudrate", 9600.0)) + self._slave_address = int(self.config.get("slave_address", 1)) + self._timeout = float(self.config.get("timeout", 1.0)) + + # 串口对象 + self._serial = None + + # 温度监控相关(内部状态) + self._monitoring_task = None + self._target_temperature_internal = -999.0 # 内部使用,表示未设置 + self._tolerance_internal = 0.5 + self._monitoring_internal = False + self._alarm_triggered_internal = False + self._alarm_status_internal = "Idle" + self._monitor_interval = 1.0 # 监控间隔(秒) + + # 硬约束:所有数值属性必须对齐为 float,不能用 None + # target_temperature 用 -999.0 表示未设置 + self.data = { + "status": "Idle", + "temperature": 0.0, + "target_temperature": -999.0, # 用特殊值表示未设置 + "tolerance": 0.5, + "monitoring": False, + "alarm_triggered": False, + "alarm_status": "Idle", + "offset": 0.0, + "unit": "℃", + "slave_address": float(self._slave_address), + "baudrate": float(self._baudrate), + "level": False, + "rssi": 0.0, + } + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + # ==================== 属性(全部使用简单类型,不用 Optional)==================== + + @property + def status(self) -> str: + return self.data.get("status", "Idle") + + @property + def temperature(self) -> float: + return float(self.data.get("temperature", 0.0)) + + @property + def target_temperature(self) -> float: + """目标温度阈值,-999.0 表示未设置""" + return float(self.data.get("target_temperature", -999.0)) + + @property + def tolerance(self) -> float: + """允许误差范围""" + return float(self.data.get("tolerance", 0.5)) + + @property + def monitoring(self) -> bool: + """是否正在监控""" + return bool(self.data.get("monitoring", False)) + + @property + def alarm_triggered(self) -> bool: + """是否已触发提醒""" + return bool(self.data.get("alarm_triggered", False)) + + @property + def alarm_status(self) -> str: + """告警状态: Idle/Monitoring/Reached/Timeout/Error""" + return str(self.data.get("alarm_status", "Idle")) + + @property + def offset(self) -> float: + return float(self.data.get("offset", 0.0)) + + @property + def unit(self) -> str: + return str(self.data.get("unit", "℃")) + + @property + def slave_address(self) -> float: + return float(self.data.get("slave_address", 1.0)) + + @property + def baudrate(self) -> float: + return float(self.data.get("baudrate", 9600.0)) + + @property + def level(self) -> bool: + return bool(self.data.get("level", False)) + + @property + def rssi(self) -> float: + return float(self.data.get("rssi", 0.0)) + + # ==================== 串口底层通信 ==================== + + def _open_serial(self): + if serial is None: + raise ImportError("pyserial 未安装") + if self._serial is not None and self._serial.is_open: + return + self._serial = serial.Serial( + port=self._port, + baudrate=int(self._baudrate), + bytesize=serial.EIGHTBITS, + parity=serial.PARITY_NONE, + stopbits=serial.STOPBITS_ONE, + timeout=self._timeout, + ) + + def _close_serial(self): + if self._serial is not None and self._serial.is_open: + self._serial.close() + self._serial = None + + def _send_and_receive(self, request: bytes, expected_resp_len: int = 64) -> bytes: + if self._serial is None or not self._serial.is_open: + raise ConnectionError("串口未打开") + self._serial.reset_input_buffer() + self._serial.write(request) + time_module.sleep(0.05) + resp = self._serial.read(expected_resp_len) + return resp + + def _read_registers(self, start_reg: int, reg_count: int, func_code: int = 0x03) -> bytes: + request = _build_read_request(self._slave_address, func_code, start_reg, reg_count) + resp = self._send_and_receive(request, 5 + reg_count * 2 + 10) + return _validate_response(resp, self._slave_address, func_code) + + def _write_single_register(self, reg_addr: int, value: int): + request = _build_write_single_request(self._slave_address, reg_addr, value) + resp = self._send_and_receive(request, 20) + _validate_response(resp, self._slave_address, 0x06) + + def _write_multiple_registers(self, start_reg: int, values: List[int]): + request = _build_write_multiple_request(self._slave_address, start_reg, values) + resp = self._send_and_receive(request, 20) + _validate_response(resp, self._slave_address, 0x10) + + # ==================== 异步动作方法 ==================== + + @action(description="初始化设备") + async def initialize(self) -> bool: + try: + self.data["status"] = "Busy" + self._open_serial() + # 简单验证连接,读取实时温度 + temp = _decode_float_abcd(*struct.unpack(">HH", self._read_registers(0x0002, 2))) + self.data["temperature"] = float(temp) + self.data["status"] = "Idle" + return True + except Exception as e: + self.data["status"] = "Error" + self.logger.error(f"初始化失败: {e}") + return False + + @action(description="清理资源") + async def cleanup(self) -> bool: + # 停止监控任务 + if self._monitoring_task is not None: + self._monitoring_task.cancel() + try: + await self._monitoring_task + except asyncio.CancelledError: + pass + self._monitoring_task = None + + self._close_serial() + self.data["status"] = "Offline" + self.data["monitoring"] = False + return True + + async def read_temperature(self) -> float: + """读取当前温度""" + try: + self.data["status"] = "Busy" + data = self._read_registers(0x0002, 2) + temp = _decode_float_abcd(struct.unpack(">H", data[0:2])[0], struct.unpack(">H", data[2:4])[0]) + self.data["temperature"] = float(temp) + self.data["status"] = "Idle" + return float(temp) + except Exception as e: + self.data["status"] = "Error" + raise + + # ==================== 温度监控功能(参数全部使用 float,不用 Optional)==================== + + async def set_target_temperature(self, target: float) -> bool: + """设置目标温度阈值""" + try: + self.data["target_temperature"] = float(target) + self._target_temperature_internal = float(target) + self.logger.info(f"目标温度已设置为: {target}°C") + return True + except Exception as e: + self.logger.error(f"设置目标温度失败: {e}") + return False + + async def set_tolerance(self, tolerance: float) -> bool: + """设置允许误差范围""" + try: + self.data["tolerance"] = float(tolerance) + self._tolerance_internal = float(tolerance) + self.logger.info(f"误差范围已设置为: {tolerance}°C") + return True + except Exception as e: + self.logger.error(f"设置误差范围失败: {e}") + return False + + async def _monitor_temperature_loop(self, target: float, tolerance: float, timeout: float): + """温度监控循环""" + start_time = time_module.time() + self.data["alarm_status"] = "Monitoring" + + while self._monitoring_internal: + try: + # 读取当前温度 + current_temp = await self.read_temperature() + self.logger.debug(f"当前温度: {current_temp}°C, 目标: {target}°C, 误差: {tolerance}°C") + + # 检查是否达到目标温度 + if abs(current_temp - target) <= tolerance: + self.data["alarm_triggered"] = True + self.data["alarm_status"] = "Reached" + self._alarm_triggered_internal = True + self._monitoring_internal = False + self.logger.info(f"温度已达到目标! 当前: {current_temp}°C, 目标: {target}°C") + + # 触发回调(如果有 ROS 节点) + if self._ros_node is not None: + self._ros_node.get_logger().info(f"Temperature reached target: {current_temp}°C") + return + + # 检查超时(timeout > 0 表示有限制) + if timeout > 0.0: + elapsed = time_module.time() - start_time + if elapsed > timeout: + self.data["alarm_status"] = "Timeout" + self._monitoring_internal = False + self.logger.warning(f"温度监控超时: {timeout}秒") + return + + # 等待下一次检查 + if self._ros_node is not None: + await self._ros_node.sleep(self._monitor_interval) + else: + await asyncio.sleep(self._monitor_interval) + + except asyncio.CancelledError: + self.data["alarm_status"] = "Cancelled" + self.logger.info("温度监控已取消") + raise + except Exception as e: + self.data["alarm_status"] = "Error" + self.logger.error(f"温度监控错误: {e}") + self._monitoring_internal = False + raise + + async def start_temperature_monitoring(self, target: float, tolerance: float = 0.5, timeout: float = 0.0) -> bool: + """ + 开始后台监控温度,达到目标后触发提醒 + + Args: + target: 目标温度 (°C) + tolerance: 允许误差范围 (°C),默认 0.5 + timeout: 超时时间(秒),0.0 表示不限制 + + Returns: + bool: 是否成功启动监控 + """ + try: + # 如果已有监控任务在运行,先停止 + if self._monitoring_task is not None and not self._monitoring_task.done(): + self._monitoring_task.cancel() + try: + await self._monitoring_task + except asyncio.CancelledError: + pass + + # 重置状态 + self._target_temperature_internal = float(target) + self._tolerance_internal = float(tolerance) + self._monitoring_internal = True + self._alarm_triggered_internal = False + + # 更新 data 字典 + self.data["target_temperature"] = float(target) + self.data["tolerance"] = float(tolerance) + self.data["monitoring"] = True + self.data["alarm_triggered"] = False + self.data["alarm_status"] = "Idle" + + # 启动后台监控任务 + self._monitoring_task = asyncio.create_task( + self._monitor_temperature_loop(target, tolerance, timeout) + ) + + self.logger.info(f"开始监控温度: 目标 {target}°C, 误差 ±{tolerance}°C") + return True + + except Exception as e: + self.data["alarm_status"] = "Error" + self.logger.error(f"启动温度监控失败: {e}") + return False + + async def stop_temperature_monitoring(self) -> bool: + """停止温度监控""" + try: + self._monitoring_internal = False + + if self._monitoring_task is not None and not self._monitoring_task.done(): + self._monitoring_task.cancel() + try: + await self._monitoring_task + except asyncio.CancelledError: + pass + self._monitoring_task = None + + self.data["monitoring"] = False + if self.data["alarm_status"] == "Monitoring": + self.data["alarm_status"] = "Cancelled" + + self.logger.info("温度监控已停止") + return True + + except Exception as e: + self.logger.error(f"停止温度监控失败: {e}") + return False + + async def wait_for_temperature(self, target: float, tolerance: float = 0.5, timeout: float = 300.0) -> bool: + """ + 阻塞等待温度达到目标值(用于工作流串联) + + Args: + target: 目标温度 (°C) + tolerance: 允许误差范围 (°C),默认 0.5 + timeout: 超时时间(秒),默认 300 秒 + + Returns: + bool: 是否成功达到目标温度(False 表示超时或错误) + """ + try: + self.data["status"] = "Busy" + + # 重置状态 + self._target_temperature_internal = float(target) + self._tolerance_internal = float(tolerance) + self._monitoring_internal = True + self._alarm_triggered_internal = False + + # 更新 data 字典 + self.data["target_temperature"] = float(target) + self.data["tolerance"] = float(tolerance) + self.data["monitoring"] = True + self.data["alarm_triggered"] = False + self.data["alarm_status"] = "Monitoring" + + start_time = time_module.time() + + while self._monitoring_internal: + # 读取当前温度 + current_temp = await self.read_temperature() + + # 检查是否达到目标温度 + if abs(current_temp - target) <= tolerance: + self.data["alarm_triggered"] = True + self.data["alarm_status"] = "Reached" + self._monitoring_internal = False + self.data["status"] = "Idle" + self.logger.info(f"温度已达到目标! 当前: {current_temp}°C, 目标: {target}°C") + return True + + # 检查超时 + if timeout > 0.0: + elapsed = time_module.time() - start_time + if elapsed > timeout: + self.data["alarm_status"] = "Timeout" + self._monitoring_internal = False + self.data["status"] = "Idle" + self.logger.warning(f"等待温度超时: {timeout}秒") + return False + + # 等待下一次检查 + if self._ros_node is not None: + await self._ros_node.sleep(self._monitor_interval) + else: + await asyncio.sleep(self._monitor_interval) + + self.data["status"] = "Idle" + return False + + except asyncio.CancelledError: + self.data["alarm_status"] = "Cancelled" + self.data["status"] = "Idle" + raise + except Exception as e: + self.data["alarm_status"] = "Error" + self.data["status"] = "Error" + self.logger.error(f"等待温度失败: {e}") + return False + + # ==================== 其他动作方法 ==================== + + async def set_offset(self, offset: float) -> bool: + try: + self.data["status"] = "Busy" + h, l = _encode_float_abcd(float(offset)) + self._write_multiple_registers(0x0108, [h, l]) + self.data["offset"] = float(offset) + self.data["status"] = "Idle" + return True + except Exception: + self.data["status"] = "Error" + return False + + async def set_unit(self, unit: float) -> bool: + try: + self.data["status"] = "Busy" + self._write_single_register(0x0130, int(unit)) + self.data["unit"] = UNIT_MAP.get(float(unit), "℃") + self.data["status"] = "Idle" + return True + except Exception: + self.data["status"] = "Error" + return False + + async def set_slave_address(self, address: float) -> bool: + try: + self.data["status"] = "Busy" + self._write_single_register(0x012C, int(address)) + self._slave_address = int(address) + self.data["slave_address"] = float(address) + self.data["status"] = "Idle" + return True + except Exception: + self.data["status"] = "Error" + return False + + async def set_baudrate(self, baudrate: float) -> bool: + try: + self.data["status"] = "Busy" + code = BAUDRATE_REVERSE_MAP.get(float(baudrate)) + if code is None: return False + self._write_single_register(0x012D, int(code)) + self._close_serial() + self._baudrate = float(baudrate) + self.data["baudrate"] = float(baudrate) + self.data["status"] = "Idle" + return True + except Exception: + self.data["status"] = "Error" + return False \ No newline at end of file diff --git a/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml new file mode 100644 index 0000000..9de4121 --- /dev/null +++ b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml @@ -0,0 +1,76 @@ +jyhsm_temperature_transmitter: + category: + - sensor + class: + module: unilabos.devices.sensor.jyhsm_temperature_transmitter:JyhsmTemperatureTransmitter + type: python + status_types: + status: str + temperature: float + offset: float + unit: str + slave_address: float + baudrate: float + target_temperature: float + tolerance: float + monitoring: bool + alarm_triggered: bool + alarm_status: str + level: bool + rssi: float + action_value_mappings: + read_temperature: + parameters: {} + set_offset: + parameters: + offset: float + set_unit: + parameters: + unit: float + set_slave_address: + parameters: + address: float + set_baudrate: + parameters: + baudrate: float + set_target_temperature: + parameters: + target: float + set_tolerance: + parameters: + tolerance: float + start_temperature_monitoring: + parameters: + target: float + tolerance: float + timeout: float + stop_temperature_monitoring: + parameters: {} + wait_for_temperature: + parameters: + target: float + tolerance: float + timeout: float + config_info: [] + description: JYHSM一体化温度变送器,安徽久跃仪表有限公司生产。通过Modbus RTU协议(RS485)通信,支持实时温度监测、温度偏移校准、单位切换等功能。新增温度阈值监控功能,可设置目标温度并在达到时触发提醒,适用于实验过程监控和自动化工作流。 + handles: [] + icon: '' + init_param_schema: + config: + properties: + port: + default: COM4 + type: string + baudrate: + default: 9600 + type: integer + slave_address: + default: 1 + type: integer + timeout: + default: 1.0 + type: number + required: + - port + type: object + version: 1.0.0 \ No newline at end of file diff --git a/device_package_example/devices/longer_bt100/graph_longer_bt100.json b/device_package_example/devices/longer_bt100/graph_longer_bt100.json new file mode 100644 index 0000000..d8a420a --- /dev/null +++ b/device_package_example/devices/longer_bt100/graph_longer_bt100.json @@ -0,0 +1,20 @@ +{ + "nodes": [ + { + "id": "longer_bt100_1", + "name": "兰格蠕动泵BT100-2J", + "children": [], + "parent": null, + "type": "device", + "class": "longer_bt100", + "position": {"x": 0, "y": 0, "z": 0}, + "config": { + "port": "COM4", + "baudrate": 1200, + "address": 1, + "serial_timeout": 0.5 + }, + "data": {} + } + ] +} \ No newline at end of file diff --git a/device_package_example/devices/longer_bt100/longer_bt100.py b/device_package_example/devices/longer_bt100/longer_bt100.py new file mode 100644 index 0000000..4afa672 --- /dev/null +++ b/device_package_example/devices/longer_bt100/longer_bt100.py @@ -0,0 +1,607 @@ +""" +兰格 BT100-2J 蠕动泵驱动 +通信协议: RS485, 1200bps, 8N1E (8data + 1even parity + 1stop) + +帧格式: flag(E9) + addr + len + PDU + FCS +字节填充: flag 之后,E8→E8 00, E9→E8 01 (len/FCS 按原始数据计算) +""" +import logging +import time as time_module +from typing import Dict, Any, Optional + +import serial + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + # 降级处理:如果没有装饰器,定义空装饰器 + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="longer_bt100", + category=["pump"], + description="兰格 BT100-2J 蠕动泵,RS485 通信", + display_name="兰格蠕动泵" +) +class LongerBT100: + """兰格 BT100-2J 蠕动泵驱动 (WJ/RJ ASCII 协议)""" + _ros_node: "BaseROS2DeviceNode" + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and 'id' in kwargs: + device_id = kwargs.pop('id') + if config is None and 'config' in kwargs: + config = kwargs.pop('config') + self.device_id = device_id or "longer_bt100" + self.config = config or {} + self.port = self.config.get("port", "COM4") + self.baudrate = self.config.get("baudrate", 1200) + self.address = self.config.get("address", 1) + # 1200bps 下一帧约百毫秒量级,略放大避免 read 截断 + self._serial_timeout = float(self.config.get("serial_timeout", 0.5)) + self.logger = logging.getLogger(f"LongerBT100.{self.device_id}") + self.ser: Optional[serial.Serial] = None + + # 内部状态跟踪 + self._current_speed = 0.0 # 当前转速 (RPM) + self._current_direction = 1 # 当前方向 (1=顺时针CW, 0=逆时针CCW) + self._current_fullspeed = False # 当前是否全速模式 + + # 预填充所有属性字段(硬约束) + self.data = { + "status": "Idle", + "speed": 0.0, + "direction": "CW", + "is_fullspeed": False + } + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + @action(description="初始化设备") + async def initialize(self) -> bool: + """初始化串口连接""" + try: + self.ser = serial.Serial( + self.port, + self.baudrate, + parity=serial.PARITY_EVEN, # 协议要求: 8data + 1even parity + 1stop + stopbits=serial.STOPBITS_ONE, + timeout=self._serial_timeout, + ) + self.data["status"] = "Idle" + self.logger.info(f"Connected to BT100-2J on {self.port} at {self.baudrate}bps") + return True + except Exception as e: + self.logger.error(f"Serial Error: {e}") + self.data["status"] = "Error" + return False + + @action(description="清理资源") + async def cleanup(self) -> bool: + """关闭串口连接""" + try: + if self.ser and self.ser.is_open: + self.ser.close() + self.data["status"] = "Offline" + return True + except Exception as e: + self.logger.error(f"Cleanup Error: {e}") + return False + + # ========== 字节填充/解填充 ========== + + def _escape_encode(self, data: bytes) -> bytes: + """编码: E8→E8 00, E9→E8 01 (应用于 flag 之后的内容)""" + result = bytearray() + for b in data: + if b == 0xE8: + result.extend([0xE8, 0x00]) + elif b == 0xE9: + result.extend([0xE8, 0x01]) + else: + result.append(b) + return bytes(result) + + def _escape_decode(self, data: bytes) -> bytes: + """解码: E8 00→E8, E8 01→E9""" + result = bytearray() + i = 0 + while i < len(data): + if i + 1 < len(data) and data[i] == 0xE8: + if data[i + 1] == 0x00: + result.append(0xE8) + i += 2 + elif data[i + 1] == 0x01: + result.append(0xE9) + i += 2 + else: + result.append(data[i]) + i += 1 + else: + result.append(data[i]) + i += 1 + return bytes(result) + + # ========== 帧构建/解析 ========== + + def _calc_fcs(self, addr: int, pdu: bytes) -> int: + """计算校验字节 FCS: addr ^ len(pdu) ^ pdu 各字节异或""" + xor_val = addr ^ len(pdu) + for b in pdu: + xor_val ^= b + return xor_val & 0xFF + + def _build_frame(self, pdu: bytes) -> bytes: + """构建完整帧: flag(E9) + escaped(addr + len + pdu + fcs)""" + # 计算原始 FCS(按未填充数据) + fcs = self._calc_fcs(self.address, pdu) + # 原始数据: addr + len + pdu + fcs + raw_payload = bytes([self.address, len(pdu)]) + pdu + bytes([fcs]) + # 对 flag 之后的内容进行字节填充 + escaped_payload = self._escape_encode(raw_payload) + # 完整帧 + return bytes([0xE9]) + escaped_payload + + def _read_exact(self, n: int) -> Optional[bytes]: + """读取精确 n 字节,超时返回 None""" + buf = bytearray() + while len(buf) < n: + chunk = self.ser.read(n - len(buf)) + if not chunk: + return None + buf.extend(chunk) + return bytes(buf) + + def _read_response_frame(self, timeout_extra: float = 0.2) -> Optional[bytes]: + """读取应答帧: 同步 0xE9 帧头,然后读取并解填充""" + if not self.ser or not self.ser.is_open: + return None + + # 同步帧头 + start_time = time_module.time() + while time_module.time() - start_time < timeout_extra + self._serial_timeout: + b = self.ser.read(1) + if not b: + self.logger.debug("sync 0xE9: timeout") + return None + if b[0] == 0xE9: + break + else: + self.logger.warning("sync 0xE9: 超时未找到帧头") + return None + + # 读取后续数据(先读 addr + len,再根据 len 读剩余) + # 注意:由于字节填充,物理长度可能大于逻辑长度 + # 策略:读取足够多的字节,然后解填充 + raw_buf = bytearray() + max_read = 64 # 读取最多 64 字节 + start_time = time_module.time() + while len(raw_buf) < max_read: + b = self.ser.read(1) + if not b: + break + raw_buf.append(b[0]) + # 检查是否已读取完整帧(解填充后) + decoded = self._escape_decode(bytes(raw_buf)) + if len(decoded) >= 3: + addr, pdu_len = decoded[0], decoded[1] + expected_total = 3 + pdu_len + 1 # addr(1) + len(1) + pdu(pdu_len) + fcs(1) + if len(decoded) >= expected_total: + return bytes([0xE9]) + bytes(raw_buf[:len(decoded) + (len(raw_buf) - len(decoded) + 1) // 1]) + if time_module.time() - start_time > timeout_extra + self._serial_timeout: + break + + # 尝试解填充 + decoded = self._escape_decode(bytes(raw_buf)) + if len(decoded) >= 3: + return bytes([0xE9]) + bytes(raw_buf) + return None + + def _parse_response(self, raw_frame: bytes) -> Optional[dict]: + """解析应答帧,返回解填充后的帧数据""" + if not raw_frame or len(raw_frame) < 5: + return None + # 跳过帧头 0xE9,解填充剩余内容 + # payload 格式: addr(1) + len(1) + PDU(len) + FCS(1) + payload = self._escape_decode(raw_frame[1:]) + if len(payload) < 3: + return None + addr, pdu_len = payload[0], payload[1] + # 需要的总长度: addr(1) + len(1) + PDU(pdu_len) + FCS(1) = 3 + pdu_len + if len(payload) < 3 + pdu_len: + self.logger.warning(f"Payload 长度不足: got {len(payload)}, need {3 + pdu_len}") + return None + pdu = payload[2:2 + pdu_len] + fcs = payload[2 + pdu_len] + # 校验 FCS + expected_fcs = self._calc_fcs(addr, pdu) + if fcs != expected_fcs: + self.logger.warning(f"FCS 校验失败: got 0x{fcs:02X}, expected 0x{expected_fcs:02X}") + return None + return { + "addr": addr, + "pdu": pdu, + "fcs": fcs + } + + # ========== 命令发送 ========== + + def _send_wj_command(self, speed: float, run_state: int, dir_state: int, fullspeed: int = 0) -> Optional[bytes]: + """发送 WJ 设置运行参数命令 + + PDU格式: WJ(57 4A) + 转速(2字节,高位在前,单位0.1RPM) + 全速启停(1字节) + 方向(1字节) + + 参数: + speed: 转速 (RPM) + run_state: 启停状态 (1=运行, 0=停止) + dir_state: 方向状态 (1=顺时针CW, 0=逆时针CCW) + fullspeed: 全速标志 (1=全速, 0=正常) + + 示例 (50.0 RPM 正常顺时针运行): + E9 01 06 57 4A 01 F4 01 01 EF + """ + # 转速转换为 0.1 RPM 单位 (高位在前) + speed_val = int(speed * 10) + speed_hi = (speed_val >> 8) & 0xFF + speed_lo = speed_val & 0xFF + + # 全速/启停状态字节: Bit0=启停, Bit1=全速 + status_byte = (run_state & 0x01) | ((fullspeed & 0x01) << 1) + + # 方向状态字节: Bit0=方向 (1=CW, 0=CCW) + dir_byte = dir_state & 0x01 + + # 构建 PDU: WJ + 转速 + 状态 + 方向 + pdu = bytearray([0x57, 0x4A, speed_hi, speed_lo, status_byte, dir_byte]) + + # 构建完整帧 + frame = self._build_frame(pdu) + + self.logger.info(f"[TX] Frame: {frame.hex()} (speed={speed}RPM, run={run_state}, dir={dir_state}, fullspeed={fullspeed})") + self.ser.reset_input_buffer() + self.ser.write(frame) + + # 广播地址(31)无应答 + if self.address == 31: + self.logger.info("广播地址,无应答") + return None + + response = self._read_response_frame() + if response: + self.logger.info(f"[RX] Response: {response.hex()}") + else: + self.logger.warning("[RX] 无有效应答帧") + return response + + def _send_rj_command(self) -> Optional[dict]: + """发送 RJ 读取运行参数命令 + + PDU格式: RJ(52 4A) + 响应格式: RJ + 转速(2字节) + 全速启停(1字节) + 方向(1字节) + + 示例: + 发送: E9 01 02 52 4A 1B + 响应: E9 01 06 52 4A 02 E8 01 01 01 F4 (解码后) + 转速=0x02E8=740→74.0RPM, 启停=01运行, 全速=0正常, 方向=01顺时针 + """ + pdu = bytearray([0x52, 0x4A]) + frame = self._build_frame(pdu) + + self.logger.info(f"[TX] RJ Query: {frame.hex()}") + self.ser.reset_input_buffer() + self.ser.write(frame) + + response = self._read_response_frame() + if not response: + self.logger.warning("[RX] RJ 无有效应答帧") + return None + self.logger.info(f"[RX] Response: {response.hex()}") + + parsed = self._parse_response(response) + if not parsed: + return None + + pdu_resp = parsed["pdu"] + # PDU 格式: RJ(52 4A) + 转速2字节 + 状态1字节 + 方向1字节 + if len(pdu_resp) < 6: + self.logger.warning(f"RJ 响应 PDU 长度不足: {len(pdu_resp)}") + return None + + speed_val = (pdu_resp[2] << 8) | pdu_resp[3] + speed = speed_val / 10.0 + status_byte = pdu_resp[4] + dir_byte = pdu_resp[5] + + run_state = status_byte & 0x01 # Bit0: 启停 + fullspeed = (status_byte >> 1) & 0x01 # Bit1: 全速 + direction = "CW" if (dir_byte & 0x01) else "CCW" + + return { + "speed": speed, + "running": run_state == 1, + "fullspeed": fullspeed == 1, + "direction": direction + } + + # ========== 动作方法 (Uni-Lab-OS 标准接口) ========== + + @action(description="启动泵") + async def start(self, **kwargs): + """ + 启动泵转动(使用当前转速和方向) + """ + self._send_wj_command( + self._current_speed, + 1, # 运行 + self._current_direction, + 1 if self._current_fullspeed else 0 + ) + self.data["status"] = "Busy" + self.logger.info(f"Pump {self.device_id} STARTED at {self._current_speed} RPM") + + @action(description="停止泵") + async def stop(self, **kwargs): + """ + 停止泵转动 + """ + self._send_wj_command( + self._current_speed, + 0, # 停止 + self._current_direction, + 0 + ) + self.data["status"] = "Idle" + self.logger.info(f"Pump {self.device_id} STOPPED") + + @action(description="设置转速") + async def set_speed(self, speed: float, **kwargs): + """ + 设置转速 + + Args: + speed[转速]: 泵的转速 (RPM) + + 注意: + - 如果泵正在运行,会立即改变转速并继续运行 + - 如果泵停止,只更新内部转速值,下次 start() 时使用 + """ + self._current_speed = float(speed) + + # 如果泵正在运行,立即更新转速 + if self.data["status"] == "Busy": + self._send_wj_command( + self._current_speed, + 1, + self._current_direction, + 1 if self._current_fullspeed else 0 + ) + + self.data["speed"] = self._current_speed + self.logger.info(f"Pump {self.device_id} SPEED set to {self._current_speed} RPM") + + @action(description="设置转动方向") + async def set_direction(self, direction: str, **kwargs): + """ + 设置转动方向 + + Args: + direction[方向]: "CW" (顺时针) 或 "CCW" (逆时针) + """ + if direction.upper() == "CW": + self._current_direction = 1 + self.data["direction"] = "CW" + elif direction.upper() == "CCW": + self._current_direction = 0 + self.data["direction"] = "CCW" + else: + self.logger.warning(f"Invalid direction: {direction}, using CW") + self._current_direction = 1 + self.data["direction"] = "CW" + + # 如果泵正在运行,立即更新方向 + if self.data["status"] == "Busy": + self._send_wj_command( + self._current_speed, + 1, + self._current_direction, + 1 if self._current_fullspeed else 0 + ) + + self.logger.info(f"Pump {self.device_id} DIRECTION set to {self.data['direction']}") + + async def set_fullspeed(self, enable: bool, **kwargs): + """设置全速模式 + + 参数: + enable: True 启用全速模式,False 正常模式 + """ + self._current_fullspeed = bool(enable) + self.data["is_fullspeed"] = self._current_fullspeed + + # 如果泵正在运行,立即更新 + if self.data["status"] == "Busy": + self._send_wj_command( + self._current_speed, + 1, + self._current_direction, + 1 if self._current_fullspeed else 0 + ) + + self.logger.info(f"Pump {self.device_id} FULLSPEED set to {self._current_fullspeed}") + + async def read_status(self, **kwargs): + """读取泵的当前运行状态""" + result = self._send_rj_command() + if result: + self.data["speed"] = result["speed"] + self.data["status"] = "Busy" if result["running"] else "Idle" + self.data["direction"] = result["direction"] + self.data["is_fullspeed"] = result["fullspeed"] + self._current_speed = result["speed"] + self._current_direction = 1 if result["direction"] == "CW" else 0 + self._current_fullspeed = result["fullspeed"] + self.logger.info( + f"Pump status: speed={result['speed']}RPM, " + f"running={result['running']}, dir={result['direction']}, " + f"fullspeed={result['fullspeed']}" + ) + return result + + async def run_for_duration(self, duration: float, speed: float = None, direction: str = None, **kwargs): + """定时运行泵 + + 启动泵运行指定时间后自动停止。 + + 参数: + duration: 运行时间(秒) + speed: 转速 (RPM),可选,不指定则使用当前设置 + direction: 方向 ("CW"/"CCW"),可选,不指定则使用当前设置 + + 示例: + run_for_duration(duration=30, speed=50.0, direction="CW") + run_for_duration(duration=60) # 使用当前设置运行60秒 + """ + import asyncio + + # 设置参数(如果提供) + if speed is not None: + await self.set_speed(speed) + if direction is not None: + await self.set_direction(direction) + + # 记录开始时间 + self.logger.info(f"Pump {self.device_id} starting timed run: {duration}s at {self._current_speed} RPM {self.data['direction']}") + + # 启动泵 + await self.start() + + # 等待指定时间(使用 _ros_node.sleep 避免阻塞事件循环) + if self._ros_node is not None: + await self._ros_node.sleep(duration) + else: + # 回退:单独运行时使用 asyncio.sleep + await asyncio.sleep(duration) + + # 停止泵 + await self.stop() + + self.logger.info(f"Pump {self.device_id} completed timed run of {duration} seconds") + return { + "duration": duration, + "speed": self._current_speed, + "direction": self.data["direction"], + "status": "completed" + } + + # ========== 属性定义 (Uni-Lab-OS 标准接口) ========== + + @property + def status(self) -> str: + """泵状态: Idle / Busy / Error""" + return self.data.get("status", "Idle") + + @property + def speed(self) -> float: + """当前转速 (RPM)""" + return self.data.get("speed", 0.0) + + @property + def direction(self) -> str: + """转动方向: CW (顺时针) / CCW (逆时针)""" + return self.data.get("direction", "CW") + + @property + def is_fullspeed(self) -> bool: + """是否全速运行""" + return self.data.get("is_fullspeed", False) + + +# ========== 独立测试入口 ========== + +def _main(): + import argparse + import asyncio + + parser = argparse.ArgumentParser( + description="单独测试兰格 BT100-2J 驱动" + ) + parser.add_argument("--port", default="COM4", help="串口,如 COM4 或 /dev/ttyUSB0") + parser.add_argument("--baudrate", type=int, default=1200) + parser.add_argument("--address", type=int, default=1) + parser.add_argument("--device-id", default="test_bt100", dest="device_id") + parser.add_argument("-v", "--verbose", action="store_true") + parser.add_argument( + "--demo-run", + action="store_true", + help="执行短时 run→sleep→stop 演示(注意安全)" + ) + parser.add_argument("--demo-speed", type=float, default=50.0, dest="demo_speed") + parser.add_argument("--demo-direction", choices=("CW", "CCW"), default="CW", dest="demo_direction") + parser.add_argument("--demo-seconds", type=float, default=3.0, dest="demo_seconds") + args = parser.parse_args() + + logging.basicConfig( + level=logging.DEBUG if args.verbose else logging.INFO, + format="%(asctime)s [%(levelname)s] %(name)s: %(message)s", + ) + + async def run(): + config = { + "port": args.port, + "baudrate": args.baudrate, + "address": args.address, + } + pump = LongerBT100(device_id=args.device_id, config=config) + if not await pump.initialize(): + return 1 + try: + print("=" * 50) + print("读取泵状态...") + st = await pump.read_status() + print(f"read_status: {st}") + print(f"pump.data: {pump.data}") + + if args.demo_run: + print("=" * 50) + print(f"演示: 设置转速 {args.demo_speed} RPM, 方向 {args.demo_direction}") + await pump.set_speed(args.demo_speed) + await pump.set_direction(args.demo_direction) + print("启动泵...") + await pump.start() + print(f"运行 {args.demo_seconds} 秒...") + await asyncio.sleep(args.demo_seconds) + print("停止泵...") + await pump.stop() + st2 = await pump.read_status() + print(f"演示后状态: {st2}") + finally: + await pump.cleanup() + return 0 + + sys.exit(asyncio.run(run())) + + +if __name__ == "__main__": + import sys + _main() \ No newline at end of file diff --git a/device_package_example/devices/longer_bt100/longer_bt100.yaml b/device_package_example/devices/longer_bt100/longer_bt100.yaml new file mode 100644 index 0000000..563165d --- /dev/null +++ b/device_package_example/devices/longer_bt100/longer_bt100.yaml @@ -0,0 +1,299 @@ +longer_bt100: + category: + - longer_bt100 + class: + action_value_mappings: + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-read_status: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: read_status参数 + type: object + type: UniLabJsonCommandAsync + auto-run_for_duration: + feedback: {} + goal: {} + goal_default: + direction: null + duration: null + speed: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + direction: + type: string + duration: + type: number + speed: + type: number + required: + - duration + type: object + result: {} + required: + - goal + title: run_for_duration参数 + type: object + type: UniLabJsonCommandAsync + auto-set_direction: + feedback: {} + goal: {} + goal_default: + direction: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + direction: + type: string + required: + - direction + type: object + result: {} + required: + - goal + title: set_direction参数 + type: object + type: UniLabJsonCommandAsync + auto-set_fullspeed: + feedback: {} + goal: {} + goal_default: + enable: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + enable: + type: boolean + required: + - enable + type: object + result: {} + required: + - goal + title: set_fullspeed参数 + type: object + type: UniLabJsonCommandAsync + auto-set_speed: + feedback: {} + goal: {} + goal_default: + speed: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + speed: + type: number + required: + - speed + type: object + result: {} + required: + - goal + title: set_speed参数 + type: object + type: UniLabJsonCommandAsync + auto-start: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: start参数 + type: object + type: UniLabJsonCommandAsync + auto-stop: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: stop参数 + type: object + type: UniLabJsonCommandAsync + module: unilabos.devices.pump_and_valve.longer_bt100:LongerBT100 + status_types: + direction: str + is_fullspeed: bool + speed: float + status: str + type: python + config_info: [] + config_schema: + properties: + address: + default: 1 + description: 设备地址,1-30 为单设备,31 为广播 + maximum: 31 + minimum: 1 + type: integer + baudrate: + default: 1200 + description: 波特率,固定 1200 + type: integer + port: + default: COM4 + description: 串口设备路径,如 COM4 或 /dev/ttyUSB0 + type: string + serial_timeout: + default: 0.5 + description: 串口读取超时(秒) + type: number + type: object + description: '' + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + direction: + type: string + is_fullspeed: + type: boolean + speed: + type: number + status: + type: string + required: + - status + - speed + - direction + - is_fullspeed + type: object + version: 1.0.0 diff --git a/device_package_example/devices/runze_sy03b_t08/graph_runze_sy03b_t08.json b/device_package_example/devices/runze_sy03b_t08/graph_runze_sy03b_t08.json new file mode 100644 index 0000000..5e0cfa4 --- /dev/null +++ b/device_package_example/devices/runze_sy03b_t08/graph_runze_sy03b_t08.json @@ -0,0 +1,30 @@ +{ + "nodes": [ + { + "id": "runze_pump_1", + "name": "SY-03B注射泵", + "children": [], + "parent": null, + "type": "device", + "class": "syringe_pump_with_valve.runze.SY03B-T08", + "position": {"x": 0, "y": 0, "z": 0}, + "config": { + "port": "COM4", + "address": "1", + "max_volume": 25.0 + }, + "data": { + "status": "Offline", + "mode": 0, + "max_velocity": 0.5, + "velocity_grade": "600", + "velocity_init": "600", + "velocity_end": "600", + "valve_position": "0", + "position": 0.0, + "plunger_position": "0" + } + } + ], + "links": [] +} \ No newline at end of file diff --git a/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py b/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py new file mode 100644 index 0000000..7c2cda7 --- /dev/null +++ b/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py @@ -0,0 +1,404 @@ +""" +Runze SY-03B Ceramic Injection Pump Driver (T-08 Valve Head) +润泽 SY-03B 陶瓷注射泵驱动(T-08八通分配阀) + +Model: ZSB-SY03B-T08 +Syringe: 25mL (6000 steps full stroke) +Valve: T-08 (8-port distribution valve, C-port connects to 1-8) +Protocol: ASCII DT Format via RS232/RS485 + +Reference: SY-03B陶瓷阀芯(ASCII)V2.4 说明书 +""" + +import logging +import asyncio +import serial +import time as time_module +from typing import Dict, Any, Optional + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="runze_sy03b_t08", + category=["pump"], + description="润泽 SY-03B 陶瓷注射泵,带 T-08 八通分配阀", + display_name="润泽注射泵" +) +class RunzeSY03BT08: + """ + Runze SY-03B Ceramic Injection Pump Driver + 25mL Syringe: 6000 steps full stroke = 240 steps/mL + """ + + _ros_node: "BaseROS2DeviceNode" + + # 进样器规格配置 (mL -> 步数/mL) + SYRINGE_STEPS_PER_ML = { + 25.0: 240, # 25mL ← 用户规格 + } + + # 状态码映射 + STATUS_MAP = { + '0': "Idle", '1': "Busy", '2': "Busy", '3': "Busy", + '4': "Busy", '5': "Busy", '6': "Idle", '7': "Idle", + '8': "Idle", '9': "Idle", + } + + # 错误码映射 + ERROR_CODES = { + '?0': "Invalid Command", '?1': "Not Initialize", + '?2': "Forbidden in Current State", '?3': "Valve Error", + '?4': "Syringe Error", '?5': "Buffer Overflow", + '?6': "Invalid Address", + } + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and 'id' in kwargs: + device_id = kwargs.pop('id') + if config is None and 'config' in kwargs: + config = kwargs.pop('config') + + self.device_id = device_id or "runze_sy03b_t08" + self.config = config or {} + self.logger = logging.getLogger(f"RunzeSY03BT08.{self.device_id}") + + # 串口配置 + self.port = self.config.get('port', 'COM4') + self.baudrate = self.config.get('baudrate', 9600) + self.address = self.config.get('address', 0) + self.ascii_address = str(self.address + 1) + + # 进样器规格 + self.syringe_volume = self.config.get('syringe_volume', 25.0) + self.steps_per_ml = self.SYRINGE_STEPS_PER_ML.get(self.syringe_volume, 240) + self.max_steps = int(self.syringe_volume * self.steps_per_ml) + + # 串口连接 + self.serial: Optional[serial.Serial] = None + self._velocity = 600 + + # 数据字典 (预填充所有属性) + self.data = { + "status": "Offline", + "valve_position": "0", + "position": 0.0, + "max_velocity": 0.5, + "mode": 0, + "plunger_position": "0", + "velocity_grade": "600", + "velocity_init": "600", + "velocity_end": "600", + } + self._initialized = False + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + def _ml_to_steps(self, ml: float) -> int: + return int(ml * self.steps_per_ml) + + def _steps_to_ml(self, steps: int) -> float: + return steps / self.steps_per_ml + + def _velocity_to_ml_s(self, velocity: int) -> float: + return velocity / self.steps_per_ml * 0.5 + + def _connect(self) -> bool: + try: + if self.serial and self.serial.is_open: + return True + self.serial = serial.Serial( + port=self.port, baudrate=self.baudrate, + bytesize=serial.EIGHTBITS, parity=serial.PARITY_NONE, + stopbits=serial.STOPBITS_ONE, timeout=1.0, write_timeout=1.0 + ) + time_module.sleep(0.1) + self.logger.info(f"Serial port {self.port} opened") + return True + except Exception as e: + self.logger.error(f"Failed to open {self.port}: {e}") + return False + + def _disconnect(self): + if self.serial and self.serial.is_open: + self.serial.close() + + def _send_command(self, command: str, wait_response: bool = True) -> str: + if not self._connect(): + return "" + frame = f"/{self.ascii_address}{command}\r" + try: + if self.serial.in_waiting > 0: + self.serial.read(self.serial.in_waiting) + self.serial.write(frame.encode('ascii')) + self.logger.debug(f"Sent: {frame.strip()}") + if not wait_response: + return "" + response = b'' + start_time = time_module.time() + while time_module.time() - start_time < 5.0: + if self.serial.in_waiting > 0: + response += self.serial.read(1) + if response.endswith(b'\r\n'): + break + time_module.sleep(0.01) + return response.decode('ascii', errors='ignore') + except Exception as e: + self.logger.error(f"Communication error: {e}") + return "" + + def _parse_response(self, response: str) -> tuple: + if not response: + return ("error", "") + response = response.replace('\x03', '').replace('\r', '').replace('\n', '').strip() + if response.startswith('?'): + error_code = response[:2] + self.logger.error(f"Device error: {error_code}") + return ("error", error_code) + if response.startswith('/'): + response = response[1:] + if len(response) >= 1: + return (response[0], response[1:] if len(response) > 1 else "") + return ("unknown", response) + + def _wait_for_idle(self, timeout: float = 30.0) -> bool: + start_time = time_module.time() + while time_module.time() - start_time < timeout: + response = self._send_command("Q") + status, _ = self._parse_response(response) + if status == '0': + return True + time_module.sleep(0.1) + return False + + @action(description="初始化设备") + async def initialize(self) -> bool: + self.logger.info("Initializing SY-03B pump...") + if not self._connect(): + self.data["status"] = "Offline" + return False + try: + response = self._send_command("ZR") + status, _ = self._parse_response(response) + if status == 'error': + self.data["status"] = "Error" + return False + start_time = time_module.time() + while time_module.time() - start_time < 60.0: + response = self._send_command("Q") + status, _ = self._parse_response(response) + if status in ['0', '6', '7', '8', '9']: + self._initialized = True + self.data["status"] = "Idle" + self.data["valve_position"] = "0" + self.data["position"] = 0.0 + self.logger.info("Pump initialized") + return True + if self._ros_node: + await self._ros_node.sleep(0.2) + else: + await asyncio.sleep(0.2) + return False + except Exception as e: + self.logger.error(f"Initialization failed: {e}") + return False + + @action(description="清理资源") + async def cleanup(self) -> bool: + self._disconnect() + self.data["status"] = "Offline" + self._initialized = False + return True + + # ==================== 属性 ==================== + @property + def status(self) -> str: + return self.data.get("status", "Offline") + + @property + def valve_position(self) -> str: + return self.data.get("valve_position", "0") + + @property + def position(self) -> float: + return self.data.get("position", 0.0) + + @property + def max_velocity(self) -> float: + return self.data.get("max_velocity", 0.5) + + @property + def mode(self) -> int: + return self.data.get("mode", 0) + + @property + def plunger_position(self) -> str: + return self.data.get("plunger_position", "0") + + @property + def velocity_grade(self) -> str: + return self.data.get("velocity_grade", "600") + + @property + def velocity_init(self) -> str: + return self.data.get("velocity_init", "600") + + @property + def velocity_end(self) -> str: + return self.data.get("velocity_end", "600") + + # ==================== 动作方法 ==================== + def set_valve_position(self, position: str) -> bool: + if not self._initialized: + return False + try: + port = int(position) + if port < 1 or port > 8: + return False + except ValueError: + return False + self.data["status"] = "Busy" + response = self._send_command(f"I{port}R") + status, _ = self._parse_response(response) + if status == 'error': + self.data["status"] = "Error" + return False + if self._wait_for_idle(timeout=10.0): + self.data["valve_position"] = position + self.data["status"] = "Idle" + return True + self.data["status"] = "Error" + return False + + def set_position(self, position: float, max_velocity: float = None) -> bool: + if not self._initialized: + return False + if max_velocity is not None: + self.set_max_velocity(max_velocity) + self.data["status"] = "Busy" + steps = max(0, min(self.max_steps, self._ml_to_steps(position))) + response = self._send_command(f"A{steps}R") + status, _ = self._parse_response(response) + if status == 'error': + self.data["status"] = "Error" + return False + timeout = 30.0 + abs(steps) / 100 + if self._wait_for_idle(timeout=timeout): + self.data["position"] = position + self.data["plunger_position"] = str(steps) + self.data["status"] = "Idle" + return True + self.data["status"] = "Error" + return False + + def pull_plunger(self, volume: float) -> bool: + if not self._initialized: + return False + self.data["status"] = "Busy" + steps = self._ml_to_steps(volume) + response = self._send_command(f"P{steps}R") + status, _ = self._parse_response(response) + if status == 'error': + self.data["status"] = "Error" + return False + timeout = 10.0 + steps / 100 + if self._wait_for_idle(timeout=timeout): + current = int(self.data.get("plunger_position", "0")) + new_steps = current + steps + self.data["plunger_position"] = str(new_steps) + self.data["position"] = self._steps_to_ml(new_steps) + self.data["status"] = "Idle" + return True + self.data["status"] = "Error" + return False + + def push_plunger(self, volume: float) -> bool: + if not self._initialized: + return False + self.data["status"] = "Busy" + steps = self._ml_to_steps(volume) + response = self._send_command(f"D{steps}R") + status, _ = self._parse_response(response) + if status == 'error': + self.data["status"] = "Error" + return False + timeout = 10.0 + steps / 100 + if self._wait_for_idle(timeout=timeout): + current = int(self.data.get("plunger_position", "0")) + new_steps = max(0, current - steps) + self.data["plunger_position"] = str(new_steps) + self.data["position"] = self._steps_to_ml(new_steps) + self.data["status"] = "Idle" + return True + self.data["status"] = "Error" + return False + + def set_max_velocity(self, velocity: float) -> bool: + grade = max(10, min(6000, int(velocity * self.steps_per_ml * 2))) + response = self._send_command(f"V{grade}R") + status, _ = self._parse_response(response) + if status != 'error': + self._velocity = grade + self.data["max_velocity"] = velocity + self.data["velocity_grade"] = str(grade) + return True + return False + + def set_velocity_grade(self, velocity: str) -> bool: + try: + grade = max(10, min(6000, int(velocity))) + except ValueError: + return False + response = self._send_command(f"V{grade}R") + status, _ = self._parse_response(response) + if status != 'error': + self._velocity = grade + self.data["max_velocity"] = self._velocity_to_ml_s(grade) + self.data["velocity_grade"] = str(grade) + return True + return False + + def stop_operation(self) -> bool: + response = self._send_command("TR") + status, _ = self._parse_response(response) + self.data["status"] = "Idle" + return status != 'error' + + # 兼容接口 + def open(self) -> bool: + return True + + def close(self) -> bool: + return True + + def is_open(self) -> bool: + return True + + def is_closed(self) -> bool: + return False + + +DEVICE_CLASS = RunzeSY03BT08 \ No newline at end of file diff --git a/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.yaml b/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.yaml new file mode 100644 index 0000000..f321c9a --- /dev/null +++ b/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.yaml @@ -0,0 +1,23 @@ +runze_sy03b_t08: + class: + module: unilab_ext.devices.runze_sy03b_t08:RunzeSY03BT08 + type: python + config_schema: + type: object + properties: + port: + type: string + default: "COM4" + description: "串口端口号" + baudrate: + type: integer + default: 9600 + description: "波特率" + address: + type: integer + default: 0 + description: "设备地址开关值 (0-15)" + syringe_volume: + type: number + default: 25.0 + description: "进样器规格" \ No newline at end of file diff --git a/device_package_example/devices/xyz_guangdian/graph_example_xyz_guangdian.json b/device_package_example/devices/xyz_guangdian/graph_example_xyz_guangdian.json new file mode 100644 index 0000000..910e520 --- /dev/null +++ b/device_package_example/devices/xyz_guangdian/graph_example_xyz_guangdian.json @@ -0,0 +1,37 @@ +{ + "nodes": [ + { + "id": "xyz_guangdian_1", + "name": "XYZ光电工作台", + "children": [], + "parent": null, + "type": "device", + "class": "xyz_guangdian", + "position": {"x": 500, "y": 600, "z": 0}, + "config": { + "port": "COM35", + "baudrate": 9600, + "timeout": 2.0, + "retry_count": 3, + "retry_delay": 0.1 + }, + "data": { + "status": "Idle", + "position_x": 0.0, + "position_y": 0.0, + "position_z": 0.0, + "push_rod_status": "released", + "is_enabled": false, + "is_homed": false, + "velocity_x": 0.0, + "velocity_y": 0.0, + "velocity_z": 0.0, + "temperature": 25.0, + "error_code": 0 + } + } + ], + "edges": [], + "description": "XYZ光电工作台测试配置 - 修复版", + "version": "2.0" +} \ No newline at end of file diff --git a/device_package_example/devices/xyz_guangdian/xyz_guangdian.py b/device_package_example/devices/xyz_guangdian/xyz_guangdian.py new file mode 100644 index 0000000..d5f15cd --- /dev/null +++ b/device_package_example/devices/xyz_guangdian/xyz_guangdian.py @@ -0,0 +1,711 @@ +""" +XYZ光电工作台设备驱动 - 修复版 +用于控制XYZ三轴运动平台和推杆装置 +修复了Modbus通信错误和异步编程问题 +""" + +import logging +import time as time_module +from typing import Dict, Any, Optional +import struct + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + +@device( + id="xyz_guangdian", + category=["motion"], + description="XYZ 三维运动平台,支持三轴运动和推杆控制", + display_name="XYZ 三维平台" +) +class XYZGuangdian: + _ros_node: "BaseROS2DeviceNode" + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and 'id' in kwargs: + device_id = kwargs.pop('id') + if config is None and 'config' in kwargs: + config = kwargs.pop('config') + self.device_id = device_id or "unknown_device" + self.config = config or {} + self.logger = logging.getLogger(f"XYZGuangdian.{self.device_id}") + + # Modbus通信配置 + self.modbus_client = None + self.port = self.config.get('port', 'COM35') + self.baudrate = self.config.get('baudrate', 9600) + self.timeout = self.config.get('timeout', 2.0) + self.retry_count = self.config.get('retry_count', 3) + self.retry_delay = self.config.get('retry_delay', 0.1) + + # 设备地址映射 + self.addr_mapping = { + 'x': 0x02, # X轴地址 + 'y': 0x03, # Y轴地址 + 'z': 0x01, # Z轴地址 + 'push_rod': 0x04 # 推杆地址 + } + + # 寄存器地址映射 + self.reg_mapping = { + 'enable': 0x07, # 使能寄存器 + 'stop': 0x08, # 停止寄存器 + 'clamp': 0x07, # 夹紧寄存器 + 'release': 0x08, # 释放寄存器 + 'position': 0x03, # 位置读取寄存器 + 'target_pos': 0x04, # 目标位置寄存器 + 'speed': 0x05, # 速度寄存器 + 'accel': 0x06, # 加速度寄存器 + 'home': 0x02 # 回零寄存器 + } + + # 状态数据初始化 + self.data = { + "status": "Idle", + "position_x": 0.0, + "position_y": 0.0, + "position_z": 0.0, + "push_rod_status": "released", # 推杆状态:clamped/released + "is_enabled": False, + "is_homed": False, + "velocity_x": 0.0, + "velocity_y": 0.0, + "velocity_z": 0.0, + "temperature": 25.0, + "error_code": 0 + } + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + """与ROS节点关联""" + self._ros_node = ros_node + + @action(description="初始化设备") + async def initialize(self) -> bool: + """初始化设备""" + try: + self.logger.info(f"初始化XYZ光电工作台 {self.device_id}") + + # 导入pymodbus + try: + from pymodbus.client import ModbusSerialClient + from pymodbus.exceptions import ModbusException + except ImportError as e: + self.logger.error(f"缺少pymodbus库: {e}") + self.data["status"] = "Error" + self.data["error_code"] = 1001 + return False + + # 创建Modbus客户端 + self.modbus_client = ModbusSerialClient( + port=self.port, + baudrate=self.baudrate, + bytesize=8, + parity='N', + stopbits=1, + timeout=self.timeout + ) + + # 连接设备 + if not self.modbus_client.connect(): + self.logger.error(f"无法连接到设备端口 {self.port}") + self.data["status"] = "Error" + self.data["error_code"] = 1002 + return False + + # 测试通信 + success = await self._test_communication() + if not success: + self.logger.error("设备通信测试失败") + self.data["status"] = "Error" + self.data["error_code"] = 1003 + return False + + self.data["status"] = "Idle" + self.logger.info(f"设备 {self.device_id} 初始化成功") + return True + + except Exception as e: + self.logger.error(f"初始化失败: {e}") + self.data["status"] = "Error" + self.data["error_code"] = 1000 + return False + + async def _test_communication(self) -> bool: + """测试Modbus通信""" + for axis in ['x', 'y', 'z', 'push_rod']: + address = self.addr_mapping[axis] + try: + # 读取状态寄存器 + response = await self._read_register_safe(address, self.reg_mapping['position']) + if response is None: + self.logger.warning(f"轴 {axis} 通信测试失败") + return False + except Exception as e: + self.logger.warning(f"轴 {axis} 通信异常: {e}") + return False + + self.logger.info("所有轴通信测试成功") + return True + + async def _read_register_safe(self, address: int, register: int, count: int = 2) -> Optional[Any]: + """安全的读取寄存器操作,带重试机制""" + if not self.modbus_client or not self.modbus_client.connected: + self.logger.error("Modbus客户端未连接") + return None + + last_exception = None + for attempt in range(self.retry_count): + try: + # 清空接收缓冲区 + if hasattr(self.modbus_client, 'socket'): + try: + self.modbus_client.socket.settimeout(0.01) + self.modbus_client.socket.recv(1024) + except: + pass + + # 读取寄存器 + response = self.modbus_client.read_holding_registers( + register, count, slave=address + ) + + if response.isError(): + self.logger.warning(f"读取寄存器失败 (尝试 {attempt+1}/{self.retry_count}): {response}") + await self._ros_node.sleep(self.retry_delay) + continue + + # 成功读取 + if attempt > 0: + self.logger.info(f"第{attempt+1}次重试成功") + return response + + except Exception as e: + last_exception = e + self.logger.warning(f"读取寄存器异常 (尝试 {attempt+1}/{self.retry_count}): {e}") + await self._ros_node.sleep(self.retry_delay) + + self.logger.error(f"读取寄存器最终失败: {last_exception}") + return None + + async def _write_register_safe(self, address: int, register: int, value: int) -> bool: + """安全的写入寄存器操作,带重试机制""" + if not self.modbus_client or not self.modbus_client.connected: + self.logger.error("Modbus客户端未连接") + return False + + # 检查数值范围 + if value < 0 or value > 65535: + self.logger.error(f"寄存器值超出范围: {value} (0-65535)") + return False + + last_exception = None + for attempt in range(self.retry_count): + try: + # 清空接收缓冲区 + if hasattr(self.modbus_client, 'socket'): + try: + self.modbus_client.socket.settimeout(0.01) + self.modbus_client.socket.recv(1024) + except: + pass + + # 写入寄存器 + response = self.modbus_client.write_register( + register, value, slave=address + ) + + if response.isError(): + self.logger.warning(f"写入寄存器失败 (尝试 {attempt+1}/{self.retry_count}): {response}") + await self._ros_node.sleep(self.retry_delay) + continue + + # 验证写入 + await self._ros_node.sleep(0.05) + verify_response = await self._read_register_safe(address, register, 1) + if verify_response and verify_response.registers[0] == value: + if attempt > 0: + self.logger.info(f"第{attempt+1}次重试写入成功") + return True + else: + self.logger.warning(f"写入验证失败 (尝试 {attempt+1}/{self.retry_count})") + await self._ros_node.sleep(self.retry_delay) + continue + + except Exception as e: + last_exception = e + self.logger.warning(f"写入寄存器异常 (尝试 {attempt+1}/{self.retry_count}): {e}") + await self._ros_node.sleep(self.retry_delay) + + self.logger.error(f"写入寄存器最终失败: {last_exception}") + return False + + @action(description="清理资源") + async def cleanup(self) -> bool: + """清理设备""" + try: + self.logger.info(f"清理设备 {self.device_id}") + + # 停止所有运动 + await self.stop_all() + + # 断开连接 + if self.modbus_client and self.modbus_client.connected: + self.modbus_client.close() + + self.data["status"] = "Offline" + self.logger.info(f"设备 {self.device_id} 清理完成") + return True + + except Exception as e: + self.logger.error(f"清理失败: {e}") + return False + + # ========== 属性 ========== + + @property + def status(self) -> str: + """设备状态""" + return self.data.get("status", "Idle") + + @property + def position(self) -> Dict[str, float]: + """获取当前位置""" + return { + "x": self.data.get("position_x", 0.0), + "y": self.data.get("position_y", 0.0), + "z": self.data.get("position_z", 0.0) + } + + @property + def is_homed(self) -> bool: + """是否已回零""" + return self.data.get("is_homed", False) + + @property + def is_enabled(self) -> bool: + """是否已使能""" + return self.data.get("is_enabled", False) + + @property + def push_rod_status(self) -> str: + """推杆状态""" + return self.data.get("push_rod_status", "released") + + @property + def error_code(self) -> int: + """错误代码""" + return self.data.get("error_code", 0) + + # ========== 动作方法 ========== + + async def enable(self) -> bool: + """使能所有轴""" + try: + self.logger.info("使能所有轴") + + success_count = 0 + for axis in ['x', 'y', 'z']: + address = self.addr_mapping[axis] + success = await self._write_register_safe(address, self.reg_mapping['enable'], 1) + if success: + success_count += 1 + + if success_count == 3: + self.data["is_enabled"] = True + self.data["status"] = "Idle" + self.logger.info("所有轴使能成功") + return True + else: + self.logger.warning(f"部分轴使能失败 (成功: {success_count}/3)") + return False + + except Exception as e: + self.logger.error(f"使能失败: {e}") + return False + + async def disable(self) -> bool: + """禁用所有轴""" + try: + self.logger.info("禁用所有轴") + + success_count = 0 + for axis in ['x', 'y', 'z']: + address = self.addr_mapping[axis] + success = await self._write_register_safe(address, self.reg_mapping['enable'], 0) + if success: + success_count += 1 + + if success_count > 0: + self.data["is_enabled"] = False + self.data["status"] = "Idle" + self.logger.info(f"成功禁用 {success_count} 个轴") + return True + else: + self.logger.error("所有轴禁用失败") + return False + + except Exception as e: + self.logger.error(f"禁用失败: {e}") + return False + + async def go_home(self) -> bool: + """回零操作 - 修复异步等待错误""" + try: + self.logger.info("执行回零操作") + + if not self.data["is_enabled"]: + self.logger.error("设备未使能,无法回零") + return False + + self.data["status"] = "Busy" + + # 修复:使用正确的异步等待方法 + home_tasks = [] + for axis in ['x', 'y', 'z']: + address = self.addr_mapping[axis] + # 发送回零指令 + success = await self._write_register_safe(address, self.reg_mapping['home'], 1) + if not success: + self.logger.error(f"轴 {axis} 回零指令发送失败") + self.data["status"] = "Error" + return False + + # 修复:使用正确的异步等待 + await self._ros_node.sleep(2.0) # 等待回零完成 + + # 检查回零状态 + homed_axes = 0 + for axis in ['x', 'y', 'z']: + address = self.addr_mapping[axis] + response = await self._read_register_safe(address, self.reg_mapping['position'], 2) + if response: + # 读取当前位置,如果接近0则认为回零成功 + position = (response.registers[0] << 16) + response.registers[1] + if abs(position) < 100: # 100个脉冲范围内认为回零成功 + homed_axes += 1 + # 更新位置数据 + if axis == 'x': + self.data["position_x"] = 0.0 + elif axis == 'y': + self.data["position_y"] = 0.0 + elif axis == 'z': + self.data["position_z"] = 0.0 + + if homed_axes == 3: + self.data["is_homed"] = True + self.data["status"] = "Idle" + self.logger.info("回零成功") + return True + else: + self.logger.warning(f"部分轴回零失败 (成功: {homed_axes}/3)") + self.data["status"] = "Idle" + return False + + except Exception as e: + self.logger.error(f"回零失败: {e}") + self.data["status"] = "Error" + return False + + async def move_relative(self, x_delta: float = 0.0, y_delta: float = 0.0, + z_delta: float = 0.0, wait_done: bool = True) -> bool: + """相对移动 - 修复Modbus通信问题""" + try: + if not self.data["is_enabled"]: + self.logger.error("设备未使能,无法移动") + return False + + if not self.data["is_homed"]: + self.logger.warning("设备未回零,移动可能不准确") + + self.logger.info(f"相对移动: X+{x_delta}, Y+{y_delta}, Z+{z_delta}") + self.data["status"] = "Busy" + + # 转换为脉冲数 (假设1mm = 100脉冲) + pulses = { + 'x': int(x_delta * 100), + 'y': int(y_delta * 100), + 'z': int(z_delta * 100) + } + + # 发送移动指令 + success_count = 0 + for axis in ['x', 'y', 'z']: + if pulses[axis] == 0: + continue + + address = self.addr_mapping[axis] + + # 设置目标位置 + target_register = self.reg_mapping['target_pos'] + target_value = pulses[axis] + + # 将32位值拆分为两个16位寄存器 + high_word = (target_value >> 16) & 0xFFFF + low_word = target_value & 0xFFFF + + # 写入目标位置 + success1 = await self._write_register_safe(address, target_register, low_word) + success2 = await self._write_register_safe(address, target_register + 1, high_word) + + # 设置速度 + speed_value = 1000 # 默认速度 + speed_success = await self._write_register_safe(address, self.reg_mapping['speed'], speed_value) + + # 启动移动 + start_success = await self._write_register_safe(address, 0x09, 1) # 启动寄存器 + + if success1 and success2 and speed_success and start_success: + success_count += 1 + self.logger.info(f"轴 {axis} 移动指令发送成功") + else: + self.logger.warning(f"轴 {axis} 移动指令发送失败") + + if success_count == 0 and x_delta == 0 and y_delta == 0 and z_delta == 0: + self.logger.info("无移动指令") + self.data["status"] = "Idle" + return True + + if wait_done: + # 等待移动完成 + await self._ros_node.sleep(1.0) # 修复:使用正确的异步等待 + + # 检查是否到达目标 + all_reached = True + for axis in ['x', 'y', 'z']: + if pulses[axis] == 0: + continue + + address = self.addr_mapping[axis] + response = await self._read_register_safe(address, self.reg_mapping['position'], 2) + if response: + current_pos = (response.registers[0] << 16) + response.registers[1] + target_pos = pulses[axis] + + # 更新位置数据 + if axis == 'x': + self.data["position_x"] = current_pos / 100.0 + elif axis == 'y': + self.data["position_y"] = current_pos / 100.0 + elif axis == 'z': + self.data["position_z"] = current_pos / 100.0 + + if abs(current_pos - target_pos) > 10: # 10个脉冲误差范围内 + all_reached = False + self.logger.warning(f"轴 {axis} 未到达目标位置 (当前: {current_pos}, 目标: {target_pos})") + + self.data["status"] = "Idle" + if success_count > 0: + self.logger.info(f"移动完成 (成功轴: {success_count})") + return True + else: + self.logger.error("所有轴移动失败") + return False + + except Exception as e: + self.logger.error(f"移动失败: {e}") + self.data["status"] = "Error" + return False + + async def move_absolute(self, x: float = 0.0, y: float = 0.0, + z: float = 0.0, wait_done: bool = True) -> bool: + """绝对位置移动""" + try: + # 计算相对移动量 + current_pos = self.position + x_delta = x - current_pos["x"] + y_delta = y - current_pos["y"] + z_delta = z - current_pos["z"] + + return await self.move_relative(x_delta, y_delta, z_delta, wait_done) + + except Exception as e: + self.logger.error(f"绝对移动失败: {e}") + return False + + async def clamp_glass(self) -> bool: + """夹紧玻璃""" + try: + self.logger.info("执行玻璃夹紧") + + address = self.addr_mapping['push_rod'] + success = await self._write_register_safe(address, self.reg_mapping['clamp'], 1) + + if success: + self.data["push_rod_status"] = "clamped" + self.data["status"] = "Idle" + self.logger.info("玻璃夹紧成功") + return True + else: + self.logger.error("玻璃夹紧失败") + self.data["status"] = "Error" + return False + + except Exception as e: + self.logger.error(f"夹紧失败: {e}") + self.data["status"] = "Error" + return False + + async def release_glass(self) -> bool: + """释放玻璃""" + try: + self.logger.info("执行玻璃释放") + + address = self.addr_mapping['push_rod'] + success = await self._write_register_safe(address, self.reg_mapping['release'], 1) + + if success: + self.data["push_rod_status"] = "released" + self.data["status"] = "Idle" + self.logger.info("玻璃释放成功") + return True + else: + self.logger.error("玻璃释放失败") + self.data["status"] = "Error" + return False + + except Exception as e: + self.logger.error(f"释放失败: {e}") + self.data["status"] = "Error" + return False + + async def stop_all(self) -> bool: + """停止所有运动""" + try: + self.logger.info("停止所有运动") + + success_count = 0 + for axis in ['x', 'y', 'z']: + address = self.addr_mapping[axis] + success = await self._write_register_safe(address, self.reg_mapping['stop'], 1) + if success: + success_count += 1 + + # 停止推杆 + address = self.addr_mapping['push_rod'] + push_success = await self._write_register_safe(address, self.reg_mapping['stop'], 1) + if push_success: + success_count += 1 + + self.data["status"] = "Idle" + self.logger.info(f"停止指令发送完成 (成功: {success_count}/4)") + return success_count > 0 + + except Exception as e: + self.logger.error(f"停止失败: {e}") + return False + + async def get_position(self) -> Dict[str, float]: + """获取当前位置""" + try: + positions = {} + for axis in ['x', 'y', 'z']: + address = self.addr_mapping[axis] + response = await self._read_register_safe(address, self.reg_mapping['position'], 2) + if response: + position = (response.registers[0] << 16) + response.registers[1] + positions[axis] = position / 100.0 # 转换为mm + else: + positions[axis] = 0.0 + + # 更新数据 + self.data["position_x"] = positions.get('x', 0.0) + self.data["position_y"] = positions.get('y', 0.0) + self.data["position_z"] = positions.get('z', 0.0) + + return positions + + except Exception as e: + self.logger.error(f"获取位置失败: {e}") + return {"x": 0.0, "y": 0.0, "z": 0.0} + + async def reset_error(self) -> bool: + """重置错误""" + try: + self.logger.info("重置设备错误") + + success_count = 0 + for axis in ['x', 'y', 'z', 'push_rod']: + address = self.addr_mapping[axis] + success = await self._write_register_safe(address, 0x00, 0) # 错误复位寄存器 + if success: + success_count += 1 + + if success_count > 0: + self.data["error_code"] = 0 + self.data["status"] = "Idle" + self.logger.info(f"错误重置成功 (成功: {success_count}/4)") + return True + else: + self.logger.error("错误重置失败") + return False + + except Exception as e: + self.logger.error(f"错误重置失败: {e}") + return False + + async def set_speed(self, axis: str, speed: float) -> bool: + """设置轴速度 (mm/s)""" + try: + if axis not in ['x', 'y', 'z']: + self.logger.error(f"无效的轴名称: {axis}") + return False + + address = self.addr_mapping[axis] + speed_value = int(speed * 100) # 转换为脉冲/秒 + + success = await self._write_register_safe(address, self.reg_mapping['speed'], speed_value) + + if success: + self.logger.info(f"轴 {axis} 速度设置为 {speed} mm/s") + return True + else: + self.logger.error(f"轴 {axis} 速度设置失败") + return False + + except Exception as e: + self.logger.error(f"设置速度失败: {e}") + return False + + async def set_acceleration(self, axis: str, accel: float) -> bool: + """设置轴加速度 (mm/s²)""" + try: + if axis not in ['x', 'y', 'z']: + self.logger.error(f"无效的轴名称: {axis}") + return False + + address = self.addr_mapping[axis] + accel_value = int(accel * 10) # 转换为脉冲/秒² + + success = await self._write_register_safe(address, self.reg_mapping['accel'], accel_value) + + if success: + self.logger.info(f"轴 {axis} 加速度设置为 {accel} mm/s²") + return True + else: + self.logger.error(f"轴 {axis} 加速度设置失败") + return False + + except Exception as e: + self.logger.error(f"设置加速度失败: {e}") + return False \ No newline at end of file diff --git a/device_package_example/devices/xyz_guangdian/xyz_guangdian.yaml b/device_package_example/devices/xyz_guangdian/xyz_guangdian.yaml new file mode 100644 index 0000000..f74ee97 --- /dev/null +++ b/device_package_example/devices/xyz_guangdian/xyz_guangdian.yaml @@ -0,0 +1,542 @@ +xyz_guangdian: + action_value_mappings: + clamp_glass: + command: clamp_glass + description: 夹紧玻璃 + disable: + command: disable + description: 禁用所有轴 + enable: + command: enable + description: 使能所有轴 + get_position: + command: get_position + description: 获取当前位置 + go_home: + command: go_home + description: 回零操作 + move_absolute: + command: move_absolute + description: 绝对移动 + parameters: + wait_done: + default: true + type: bool + x: + default: 0.0 + type: float + unit: mm + y: + default: 0.0 + type: float + unit: mm + z: + default: 0.0 + type: float + unit: mm + move_relative: + command: move_relative + description: 相对移动 + parameters: + wait_done: + default: true + type: bool + x_delta: + default: 0.0 + type: float + unit: mm + y_delta: + default: 0.0 + type: float + unit: mm + z_delta: + default: 0.0 + type: float + unit: mm + release_glass: + command: release_glass + description: 释放玻璃 + reset_error: + command: reset_error + description: 重置错误 + set_acceleration: + command: set_acceleration + description: 设置轴加速度 + parameters: + accel: + type: float + unit: mm/s² + axis: + type: string + values: + - x + - y + - z + set_speed: + command: set_speed + description: 设置轴速度 + parameters: + axis: + type: string + values: + - x + - y + - z + speed: + type: float + unit: mm/s + stop_all: + command: stop_all + description: 停止所有运动 + category: + - xyz_guangdian + class: + action_value_mappings: + auto-clamp_glass: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: clamp_glass参数 + type: object + type: UniLabJsonCommandAsync + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-disable: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: disable参数 + type: object + type: UniLabJsonCommandAsync + auto-enable: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: enable参数 + type: object + type: UniLabJsonCommandAsync + auto-go_home: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: go_home参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-move_absolute: + feedback: {} + goal: {} + goal_default: + wait_done: true + x: 0.0 + y: 0.0 + z: 0.0 + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + wait_done: + default: true + type: boolean + x: + default: 0.0 + type: number + y: + default: 0.0 + type: number + z: + default: 0.0 + type: number + required: [] + type: object + result: {} + required: + - goal + title: move_absolute参数 + type: object + type: UniLabJsonCommandAsync + auto-move_relative: + feedback: {} + goal: {} + goal_default: + wait_done: true + x_delta: 0.0 + y_delta: 0.0 + z_delta: 0.0 + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + wait_done: + default: true + type: boolean + x_delta: + default: 0.0 + type: number + y_delta: + default: 0.0 + type: number + z_delta: + default: 0.0 + type: number + required: [] + type: object + result: {} + required: + - goal + title: move_relative参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-release_glass: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: release_glass参数 + type: object + type: UniLabJsonCommandAsync + auto-reset_error: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: reset_error参数 + type: object + type: UniLabJsonCommandAsync + auto-set_acceleration: + feedback: {} + goal: {} + goal_default: + accel: null + axis: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + accel: + type: number + axis: + type: string + required: + - axis + - accel + type: object + result: {} + required: + - goal + title: set_acceleration参数 + type: object + type: UniLabJsonCommandAsync + auto-set_speed: + feedback: {} + goal: {} + goal_default: + axis: null + speed: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + axis: + type: string + speed: + type: number + required: + - axis + - speed + type: object + result: {} + required: + - goal + title: set_speed参数 + type: object + type: UniLabJsonCommandAsync + auto-stop_all: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: stop_all参数 + type: object + type: UniLabJsonCommandAsync + module: unilabos.devices.workstation.xyz_guangdian:XYZGuangdian + status_types: + error_code: int + is_enabled: bool + is_homed: bool + position: dict + push_rod_status: str + status: str + type: python + config_info: [] + default_config: + baudrate: 9600 + port: COM35 + retry_count: 3 + retry_delay: 0.1 + timeout: 2.0 + description: '' + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + error_code: + type: integer + is_enabled: + type: boolean + is_homed: + type: boolean + position: + type: object + push_rod_status: + type: string + status: + type: string + required: + - status + - position + - is_homed + - is_enabled + - push_rod_status + - error_code + type: object + status_types: + error_code: + description: 错误代码 + type: int + is_enabled: + description: 是否使能 + type: bool + is_homed: + description: 是否回零 + type: bool + position_x: + description: X轴位置 + type: float + unit: mm + position_y: + description: Y轴位置 + type: float + unit: mm + position_z: + description: Z轴位置 + type: float + unit: mm + push_rod_status: + description: 推杆状态 + type: string + values: + - clamped + - released + status: + type: string + values: + - Idle + - Busy + - Error + - Offline + temperature: + description: 温度 + type: float + unit: °C + velocity_x: + description: X轴速度 + type: float + unit: mm/s + velocity_y: + description: Y轴速度 + type: float + unit: mm/s + velocity_z: + description: Z轴速度 + type: float + unit: mm/s + version: 1.0.0 From 9dc9b3f4a29b7f39dc8ce8f9a609b5e2336bd09c Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Tue, 9 Jun 2026 10:22:28 +0800 Subject: [PATCH 02/13] =?UTF-8?q?feat:=20=E6=B7=BB=E5=8A=A0=20XYZ=E5=85=89?= =?UTF-8?q?=E7=94=B5=E8=AE=BE=E5=A4=87=E6=B5=8B=E8=AF=95=E8=84=9A=E6=9C=AC?= =?UTF-8?q?=EF=BC=8C=E6=94=AF=E6=8C=81=E8=AE=BE=E5=A4=87=E5=88=9D=E5=A7=8B?= =?UTF-8?q?=E5=8C=96=E3=80=81=E7=8A=B6=E6=80=81=E8=AF=BB=E5=8F=96=E5=92=8C?= =?UTF-8?q?=E6=8E=A7=E5=88=B6=E5=8A=9F=E8=83=BD?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../devices/xyz_guangdian/xyz_guangdian.py | 27 +-- jidianqi_tuigan_v2.py | 178 ++++++++++++++++++ test_xyz_guangdian.py | 125 ++++++++++++ 3 files changed, 317 insertions(+), 13 deletions(-) create mode 100644 jidianqi_tuigan_v2.py create mode 100644 test_xyz_guangdian.py diff --git a/device_package_example/devices/xyz_guangdian/xyz_guangdian.py b/device_package_example/devices/xyz_guangdian/xyz_guangdian.py index d5f15cd..3c38f87 100644 --- a/device_package_example/devices/xyz_guangdian/xyz_guangdian.py +++ b/device_package_example/devices/xyz_guangdian/xyz_guangdian.py @@ -6,6 +6,7 @@ import logging import time as time_module +import asyncio from typing import Dict, Any, Optional import struct @@ -39,7 +40,7 @@ def not_action(func): display_name="XYZ 三维平台" ) class XYZGuangdian: - _ros_node: "BaseROS2DeviceNode" + _ros_node: Optional["BaseROS2DeviceNode"] = None def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): if device_id is None and 'id' in kwargs: @@ -187,12 +188,12 @@ async def _read_register_safe(self, address: int, register: int, count: int = 2) # 读取寄存器 response = self.modbus_client.read_holding_registers( - register, count, slave=address + register, count=count, device_id=address ) if response.isError(): self.logger.warning(f"读取寄存器失败 (尝试 {attempt+1}/{self.retry_count}): {response}") - await self._ros_node.sleep(self.retry_delay) + await asyncio.sleep(self.retry_delay) continue # 成功读取 @@ -203,7 +204,7 @@ async def _read_register_safe(self, address: int, register: int, count: int = 2) except Exception as e: last_exception = e self.logger.warning(f"读取寄存器异常 (尝试 {attempt+1}/{self.retry_count}): {e}") - await self._ros_node.sleep(self.retry_delay) + await asyncio.sleep(self.retry_delay) self.logger.error(f"读取寄存器最终失败: {last_exception}") return None @@ -232,16 +233,16 @@ async def _write_register_safe(self, address: int, register: int, value: int) -> # 写入寄存器 response = self.modbus_client.write_register( - register, value, slave=address + register, value, device_id=address ) if response.isError(): self.logger.warning(f"写入寄存器失败 (尝试 {attempt+1}/{self.retry_count}): {response}") - await self._ros_node.sleep(self.retry_delay) + await asyncio.sleep(self.retry_delay) continue - + # 验证写入 - await self._ros_node.sleep(0.05) + await asyncio.sleep(0.05) verify_response = await self._read_register_safe(address, register, 1) if verify_response and verify_response.registers[0] == value: if attempt > 0: @@ -249,13 +250,13 @@ async def _write_register_safe(self, address: int, register: int, value: int) -> return True else: self.logger.warning(f"写入验证失败 (尝试 {attempt+1}/{self.retry_count})") - await self._ros_node.sleep(self.retry_delay) + await asyncio.sleep(self.retry_delay) continue - + except Exception as e: last_exception = e self.logger.warning(f"写入寄存器异常 (尝试 {attempt+1}/{self.retry_count}): {e}") - await self._ros_node.sleep(self.retry_delay) + await asyncio.sleep(self.retry_delay) self.logger.error(f"写入寄存器最终失败: {last_exception}") return False @@ -392,7 +393,7 @@ async def go_home(self) -> bool: return False # 修复:使用正确的异步等待 - await self._ros_node.sleep(2.0) # 等待回零完成 + await asyncio.sleep(2.0) # 等待回零完成 # 检查回零状态 homed_axes = 0 @@ -488,7 +489,7 @@ async def move_relative(self, x_delta: float = 0.0, y_delta: float = 0.0, if wait_done: # 等待移动完成 - await self._ros_node.sleep(1.0) # 修复:使用正确的异步等待 + await asyncio.sleep(1.0) # 修复:使用正确的异步等待 # 检查是否到达目标 all_reached = True diff --git a/jidianqi_tuigan_v2.py b/jidianqi_tuigan_v2.py new file mode 100644 index 0000000..6ddca6b --- /dev/null +++ b/jidianqi_tuigan_v2.py @@ -0,0 +1,178 @@ +""" +jidianqi_tuigan.py + +RS485 Modbus relay / linear-actuator controller for CX5208W-style relay module. +This version DOES NOT use pyserial. It reuses the WinSerial object from +xyz_control_shulab.py, so it can share the same COM port with the XYZ platform. +""" + +from __future__ import annotations + +from dataclasses import dataclass +from typing import Iterable, Optional, Protocol +import time + + +class WinSerialLike(Protocol): + def reset_buffers(self) -> None: ... + def write(self, data: bytes): ... + def read(self, size: int) -> bytes: ... + + +def relay_modbus_crc(data: Iterable[int]) -> bytes: + crc = 0xFFFF + for b in data: + crc ^= b & 0xFF + for _ in range(8): + if crc & 0x0001: + crc = (crc >> 1) ^ 0xA001 + else: + crc >>= 1 + crc &= 0xFFFF + return bytes([crc & 0xFF, (crc >> 8) & 0xFF]) + + +def build_write_single_coil(slave_addr: int, coil_addr: int, on: bool) -> bytes: + payload = bytes([ + slave_addr & 0xFF, + 0x05, + (coil_addr >> 8) & 0xFF, + coil_addr & 0xFF, + 0xFF if on else 0x00, + 0x00, + ]) + return payload + relay_modbus_crc(payload) + + +def hex_bytes(data: bytes | bytearray | Iterable[int]) -> str: + return " ".join(f"{b & 0xFF:02X}" for b in data) + + +@dataclass +class RelayActuatorConfig: + slave_addr: int = 0x04 + response_wait_s: float = 0.08 + command_gap_s: float = 0.05 + strict_ack: bool = False + do1_coil: int = 0x0000 + do2_coil: int = 0x0001 + + +class RelayActuatorController: + def __init__( + self, + serial_port: WinSerialLike, + config: Optional[RelayActuatorConfig] = None, + *, + debug: bool = False, + ): + self.ser = serial_port + self.config = config or RelayActuatorConfig() + self.debug = debug + self.state = "unknown" + + def send_frame(self, frame: bytes, expected_len: int = 8) -> bytes: + self.ser.reset_buffers() + written = self.ser.write(frame) + if written is not None and int(written) != len(frame): + raise IOError(f"继电器发送不完整:{written}/{len(frame)} bytes") + + if self.debug: + print("[Relay TX]", hex_bytes(frame)) + + time.sleep(self.config.response_wait_s) + resp = self.ser.read(expected_len) + + if self.debug: + print("[Relay RX]", hex_bytes(resp) if resp else "") + + if self.config.strict_ack: + if len(resp) != expected_len: + raise TimeoutError(f"继电器响应长度不足,期望 {expected_len},实际 {len(resp)},响应={hex_bytes(resp)}") + if resp[-2:] != relay_modbus_crc(resp[:-2]): + raise ValueError(f"继电器 CRC 校验失败,响应={hex_bytes(resp)}") + if resp[:6] != frame[:6]: + raise RuntimeError(f"继电器写线圈回包异常,发送={hex_bytes(frame)},响应={hex_bytes(resp)}") + + time.sleep(self.config.command_gap_s) + return resp + + def write_coil(self, coil_addr: int, on: bool) -> bytes: + frame = build_write_single_coil(self.config.slave_addr, coil_addr, on) + return self.send_frame(frame, expected_len=8) + + def set_do1(self, on: bool) -> bytes: + return self.write_coil(self.config.do1_coil, on) + + def set_do2(self, on: bool) -> bytes: + return self.write_coil(self.config.do2_coil, on) + + def stop(self) -> None: + self.set_do1(False) + self.set_do2(False) + self.state = "stop" + + def forward(self, duration_s: float | None = None, stop_after: bool = False) -> None: + self.set_do2(False) + self.set_do1(True) + self.state = "push" + if duration_s is not None: + time.sleep(duration_s) + if stop_after: + self.stop() + + def backward(self, duration_s: float | None = None, stop_after: bool = False) -> None: + self.set_do1(False) + self.set_do2(True) + self.state = "pull" + if duration_s is not None: + time.sleep(duration_s) + if stop_after: + self.stop() + + def push(self, duration_s: float | None = None, stop_after: bool = False) -> None: + self.forward(duration_s=duration_s, stop_after=stop_after) + + def pull(self, duration_s: float | None = None, stop_after: bool = False) -> None: + self.backward(duration_s=duration_s, stop_after=stop_after) + + def go_origin_state(self) -> None: + self.pull() + + +LinearActuator485 = RelayActuatorController +LinearActuatorConfig = RelayActuatorConfig + + +def interactive_main() -> None: + from xyz_control_shulab import WinSerial, PORT, BAUDRATE + + shared_serial = WinSerial(PORT, BAUDRATE) + try: + shared_serial.open() + actuator = RelayActuatorController(shared_serial, debug=True) + print("推杆/继电器测试启动。命令:push / pull / stop / q") + actuator.go_origin_state() + while True: + cmd = input("actuator > ").strip().lower() + if cmd in {"q", "quit", "exit"}: + actuator.go_origin_state() + break + if cmd in {"push", "f", "forward"}: + actuator.push() + print("已前推。") + elif cmd in {"pull", "b", "backward"}: + actuator.pull() + print("已后退/回拉。") + elif cmd in {"stop", "s"}: + actuator.stop() + print("已停止。") + else: + print("无法识别。可用:push / pull / stop / q") + finally: + shared_serial.close() + print("串口已关闭。") + + +if __name__ == "__main__": + interactive_main() diff --git a/test_xyz_guangdian.py b/test_xyz_guangdian.py new file mode 100644 index 0000000..9d5bc8d --- /dev/null +++ b/test_xyz_guangdian.py @@ -0,0 +1,125 @@ +#!/usr/bin/env python3 +""" +XYZ光电设备测试脚本 +测试串口连接和基本功能 +""" + +import asyncio +import logging +import sys +from pathlib import Path + +# 添加设备包路径 +sys.path.insert(0, str(Path(__file__).parent / "device_package_example")) + +from devices.xyz_guangdian.xyz_guangdian import XYZGuangdian + +# 配置日志 +logging.basicConfig( + level=logging.INFO, + format='%(asctime)s - %(name)s - %(levelname)s - %(message)s' +) + +async def test_xyz_device(): + """测试XYZ光电设备""" + + # 设备配置 + config = { + 'port': '/dev/tty.usbserial-BG02ANBF', # macOS串口 + 'baudrate': 9600, + 'timeout': 2.0, + 'retry_count': 3, + 'retry_delay': 0.1 + } + + print("=" * 60) + print("XYZ光电设备测试") + print("=" * 60) + print(f"串口: {config['port']}") + print(f"波特率: {config['baudrate']}") + print("-" * 60) + + # 创建设备实例 + device = XYZGuangdian( + device_id="xyz_test_001", + config=config + ) + + try: + # 1. 初始化设备 + print("\n[1/6] 初始化设备...") + success = await device.initialize() + if not success: + print("❌ 初始化失败") + print(f"状态: {device.data['status']}") + print(f"错误码: {device.data['error_code']}") + return False + print("✅ 初始化成功") + + # 2. 读取当前状态 + print("\n[2/6] 读取设备状态...") + print(f"状态: {device.data['status']}") + print(f"X轴位置: {device.data['position_x']:.2f} mm") + print(f"Y轴位置: {device.data['position_y']:.2f} mm") + print(f"Z轴位置: {device.data['position_z']:.2f} mm") + print(f"推杆状态: {device.data['push_rod_status']}") + print(f"是否使能: {device.data['is_enabled']}") + print(f"是否回零: {device.data['is_homed']}") + + # 3. 使能设备 + print("\n[3/6] 使能设备...") + success = await device.enable() + if success: + print("✅ 使能成功") + else: + print("❌ 使能失败") + + # 4. 测试获取位置 + print("\n[4/6] 获取当前位置...") + position = await device.get_position() + if position: + print(f"✅ 位置读取成功: X={position['x']:.2f}, Y={position['y']:.2f}, Z={position['z']:.2f} mm") + else: + print("❌ 位置读取失败") + + # 5. 测试推杆释放 + print("\n[5/6] 测试推杆释放...") + success = await device.release_glass() + if success: + print("✅ 推杆释放成功") + else: + print("⚠️ 推杆释放失败(可能已经是释放状态)") + + # 6. 禁用设备 + print("\n[6/6] 禁用设备...") + success = await device.disable() + if success: + print("✅ 禁用成功") + else: + print("❌ 禁用失败") + + # 清理 + print("\n[清理] 关闭连接...") + await device.cleanup() + print("✅ 清理完成") + + print("\n" + "=" * 60) + print("测试完成!") + print("=" * 60) + return True + + except Exception as e: + print(f"\n❌ 测试过程中发生错误: {e}") + import traceback + traceback.print_exc() + return False + finally: + # 确保清理 + try: + await device.cleanup() + except: + pass + +if __name__ == "__main__": + result = asyncio.run(test_xyz_device()) + sys.exit(0 if result else 1) From 89ce6588b338cc06a6f7c9a88a281782c63c0797 Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Thu, 11 Jun 2026 21:19:00 +0800 Subject: [PATCH 03/13] =?UTF-8?q?feat:=20=E6=9B=B4=E6=96=B0=20SY-03B=20?= =?UTF-8?q?=E6=B3=A8=E5=B0=84=E6=B3=B5=E7=9A=84=E7=B1=BB=E5=90=8D=E5=B9=B6?= =?UTF-8?q?=E6=B7=BB=E5=8A=A0=E5=AE=8C=E6=95=B4=E5=AE=9E=E9=AA=8C=E5=AE=A4?= =?UTF-8?q?=E8=AE=BE=E5=A4=87=E6=8B=93=E6=89=91=E9=85=8D=E7=BD=AE?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../graph_runze_sy03b_t08.json | 2 +- .../graph_combined_lab.json | 139 ++++++++++++++++++ 2 files changed, 140 insertions(+), 1 deletion(-) create mode 100644 device_package_example/graph_combined_lab.json diff --git a/device_package_example/devices/runze_sy03b_t08/graph_runze_sy03b_t08.json b/device_package_example/devices/runze_sy03b_t08/graph_runze_sy03b_t08.json index 5e0cfa4..7c20dc6 100644 --- a/device_package_example/devices/runze_sy03b_t08/graph_runze_sy03b_t08.json +++ b/device_package_example/devices/runze_sy03b_t08/graph_runze_sy03b_t08.json @@ -6,7 +6,7 @@ "children": [], "parent": null, "type": "device", - "class": "syringe_pump_with_valve.runze.SY03B-T08", + "class": "runze_sy03b_t08", "position": {"x": 0, "y": 0, "z": 0}, "config": { "port": "COM4", diff --git a/device_package_example/graph_combined_lab.json b/device_package_example/graph_combined_lab.json new file mode 100644 index 0000000..ea428f1 --- /dev/null +++ b/device_package_example/graph_combined_lab.json @@ -0,0 +1,139 @@ +{ + "nodes": [ + { + "id": "dhjf_bath_1", + "name": "DHJF-2005A 恒温循环水浴", + "children": [], + "parent": null, + "type": "device", + "class": "dhjf_circulation_bath", + "position": {"x": 0, "y": 0, "z": 0}, + "config": {"port": "COM4", "slave_id": 1, "baudrate": 9600, "timeout": 1.0}, + "data": {} + }, + { + "id": "hk_a0_module_1", + "name": "华控模拟量输出", + "children": [], + "parent": null, + "type": "device", + "class": "hk_a0", + "position": {"x": 800, "y": 0, "z": 0}, + "config": {"slave_address": 1}, + "data": {} + }, + { + "id": "longer_bt100_1", + "name": "兰格蠕动泵BT100-2J", + "children": [], + "parent": null, + "type": "device", + "class": "longer_bt100", + "position": {"x": 400, "y": 0, "z": 0}, + "config": { + "port": "COM4", + "baudrate": 1200, + "address": 1, + "serial_timeout": 0.5 + }, + "data": {} + }, + { + "id": "jyhsm_temp_1", + "name": "JYHSM一体化温度变送器", + "children": [], + "parent": null, + "type": "device", + "class": "jyhsm_temperature_transmitter", + "position": {"x": 0, "y": 500, "z": 0}, + "config": { + "port": "COM4", + "baudrate": 9600, + "slave_address": 1, + "timeout": 1.0 + }, + "data": { + "status": "Idle", + "temperature": 0.0, + "offset": 0.0, + "unit": "℃", + "slave_address": 1, + "baudrate": 9600 + } + }, + { + "id": "runze_pump_1", + "name": "SY-03B注射泵", + "children": [], + "parent": null, + "type": "device", + "class": "runze_sy03b_t08", + "position": {"x": 400, "y": 500, "z": 0}, + "config": { + "port": "COM4", + "address": "1", + "max_volume": 25.0 + }, + "data": { + "status": "Offline", + "mode": 0, + "max_velocity": 0.5, + "velocity_grade": "600", + "velocity_init": "600", + "velocity_end": "600", + "valve_position": "0", + "position": 0.0, + "plunger_position": "0" + } + }, + { + "id": "duco_gcr5_1", + "name": "新松GCR5机械臂", + "children": [], + "parent": null, + "type": "device", + "class": "duco_gcr5", + "position": {"x": 800, "y": 500, "z": 0}, + "config": { + "ip": "192.168.1.10", + "cmd_port": 2000, + "status_port": 2001, + "timeout": 5.0 + }, + "data": {} + }, + { + "id": "xyz_guangdian_1", + "name": "XYZ光电工作台", + "children": [], + "parent": null, + "type": "device", + "class": "xyz_guangdian", + "position": {"x": 400, "y": 250, "z": 0}, + "config": { + "port": "COM35", + "baudrate": 9600, + "timeout": 2.0, + "retry_count": 3, + "retry_delay": 0.1 + }, + "data": { + "status": "Idle", + "position_x": 0.0, + "position_y": 0.0, + "position_z": 0.0, + "push_rod_status": "released", + "is_enabled": false, + "is_homed": false, + "velocity_x": 0.0, + "velocity_y": 0.0, + "velocity_z": 0.0, + "temperature": 25.0, + "error_code": 0 + } + } + ], + "links": [], + "description": "完整实验室设备拓扑 - 恒温水浴 + 模拟量输出 + 蠕动泵 + 温度变送器 + 注射泵 + 机械臂 + XYZ光电工作台", + "version": "1.0" +} From 5beebe28fa21e4c6935743fd5598eabc8b13fb59 Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Fri, 12 Jun 2026 10:53:33 +0800 Subject: [PATCH 04/13] =?UTF-8?q?Add=20solenoid=20valve=20and=20Zolix=20Om?= =?UTF-8?q?ni-=CE=BB=20device=20implementations?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Introduced solenoid_valve_4v110.yaml for the 4V110 solenoid valve configuration with action mappings and status types. - Updated xyz_guangdian.py to change error_code return type from int to float for consistency. - Corrected module path in xyz_guangdian.yaml to reflect the correct import structure. - Added graph_example_zolix_omni_lambda.json for Zolix Omni-λ device representation. - Implemented zolix_omni_lambda.py with comprehensive device control and communication methods. - Created zolix_omni_lambda.yaml for Zolix Omni-λ device configuration, including action mappings and status types. - Updated pyproject.toml and requirements.txt to include new dependencies for device communication and processing. --- .../bronkhorst_el_flow/bronkhorst_el_flow.py | 281 ++++++ .../bronkhorst_el_flow.yaml | 276 ++++++ .../graph_example_bronkhorst_el_flow.json | 21 + .../devices/chi760e/chi760e.py | 775 +++++++++++++++++ .../devices/chi760e/chi760e.yaml | 467 ++++++++++ .../chi760e/graph_example_chi760e.json | 19 + .../devices/cmos_detector/cmos_detector.py | 810 ++++++++++++++++++ .../devices/cmos_detector/cmos_detector.yaml | 546 ++++++++++++ .../graph_example_cmos_detector.json | 18 + .../cni_laser_msl_u_532.py | 282 ++++++ .../cni_laser_msl_u_532.yaml | 226 +++++ .../graph_example_cni_laser_msl_u_532.json | 24 + .../daheng_gci060505/daheng_gci060505.py | 219 +++++ .../daheng_gci060505/daheng_gci060505.yaml | 198 +++++ .../graph_example_daheng_gci060505.json | 19 + .../daheng_hd_r630c/daheng_hd_r630c.py | 511 +++++++++++ .../daheng_hd_r630c/daheng_hd_r630c.yaml | 360 ++++++++ .../graph_example_daheng_hd_r630c.json | 35 + .../dhjf_circulation_bath.yaml | 2 +- .../devices/duco_gcr5/duco_gcr5.yaml | 2 +- .../electrolytic_cell_gripper.py | 635 ++++++++++++++ .../electrolytic_cell_gripper.yaml | 185 ++++ ...aph_example_electrolytic_cell_gripper.json | 22 + .../devices/hk_a0/hk_a0.yaml | 2 +- .../jyhsm_temperature_transmitter.yaml | 2 +- .../devices/longer_bt100/longer_bt100.py | 5 +- .../devices/longer_bt100/longer_bt100.yaml | 2 +- .../runze_sy03b_t08/runze_sy03b_t08.py | 9 +- .../runze_sy03b_t08/runze_sy03b_t08.yaml | 2 +- .../graph_example_solenoid_valve_4v110.json | 18 + .../solenoid_valve_4v110.py | 234 +++++ .../solenoid_valve_4v110.yaml | 236 +++++ .../devices/xyz_guangdian/xyz_guangdian.py | 4 +- .../devices/xyz_guangdian/xyz_guangdian.yaml | 2 +- .../graph_example_zolix_omni_lambda.json | 19 + .../zolix_omni_lambda/zolix_omni_lambda.py | 662 ++++++++++++++ .../zolix_omni_lambda/zolix_omni_lambda.yaml | 456 ++++++++++ pyproject.toml | 7 + requirements.txt | 7 + 39 files changed, 7587 insertions(+), 13 deletions(-) create mode 100644 device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.py create mode 100644 device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.yaml create mode 100644 device_package_example/devices/bronkhorst_el_flow/graph_example_bronkhorst_el_flow.json create mode 100644 device_package_example/devices/chi760e/chi760e.py create mode 100644 device_package_example/devices/chi760e/chi760e.yaml create mode 100644 device_package_example/devices/chi760e/graph_example_chi760e.json create mode 100644 device_package_example/devices/cmos_detector/cmos_detector.py create mode 100644 device_package_example/devices/cmos_detector/cmos_detector.yaml create mode 100644 device_package_example/devices/cmos_detector/graph_example_cmos_detector.json create mode 100644 device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.py create mode 100644 device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.yaml create mode 100644 device_package_example/devices/cni_laser_msl_u_532/graph_example_cni_laser_msl_u_532.json create mode 100644 device_package_example/devices/daheng_gci060505/daheng_gci060505.py create mode 100644 device_package_example/devices/daheng_gci060505/daheng_gci060505.yaml create mode 100644 device_package_example/devices/daheng_gci060505/graph_example_daheng_gci060505.json create mode 100644 device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py create mode 100644 device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml create mode 100644 device_package_example/devices/daheng_hd_r630c/graph_example_daheng_hd_r630c.json create mode 100644 device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py create mode 100644 device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.yaml create mode 100644 device_package_example/devices/electrolytic_cell_gripper/graph_example_electrolytic_cell_gripper.json create mode 100644 device_package_example/devices/solenoid_valve_4v110/graph_example_solenoid_valve_4v110.json create mode 100644 device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.py create mode 100644 device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.yaml create mode 100644 device_package_example/devices/zolix_omni_lambda/graph_example_zolix_omni_lambda.json create mode 100644 device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.py create mode 100644 device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.yaml diff --git a/device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.py b/device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.py new file mode 100644 index 0000000..6bf1ee1 --- /dev/null +++ b/device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.py @@ -0,0 +1,281 @@ +""" +Bronkhorst EL-FLOW Prestige 质量流量控制器 (MFC) 驱动 +""" + +import logging +from typing import Dict, Any + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + import propar +except ImportError: + propar = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="bronkhorst_el_flow", + category=["sensor", "bronkhorst_el_flow"], + description="Bronkhorst EL-FLOW Prestige 质量流量控制器", + display_name="Bronkhorst MFC", +) +class BronkhorstElFlow: + _ros_node: "BaseROS2DeviceNode" + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and "id" in kwargs: + device_id = kwargs.pop("id") + if config is None and "config" in kwargs: + config = kwargs.pop("config") + + self.device_id = device_id or "unknown_device" + self.config = config or {} + self.logger = logging.getLogger(f"BronkhorstElFlow.{self.device_id}") + + self.data = { + "status": "Idle", + "flow": 0.0, + "setpoint": 0.0, + "temperature": 0.0, + "valve_output": 0.0, + "capacity_unit": "", + "user_tag": "", + "level": False, + "rssi": 0, + "value": 0.0, + } + + self._port = self.config.get("port") or kwargs.get("port", "COM12") + self._baudrate = int(self.config.get("baudrate") or kwargs.get("baudrate", 38400)) + self._address = int(self.config.get("address") or kwargs.get("address", 3)) + self._channel = int(self.config.get("channel") or kwargs.get("channel", 1)) + self._threshold_pct = float(self.config.get("threshold") or kwargs.get("threshold", 2.0)) + + self._instrument = None + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + async def _sleep(self, seconds: float): + if getattr(self, "_ros_node", None) is not None: + await self._ros_node.sleep(seconds) + else: + import time as _time + _time.sleep(seconds) + + @action(description="初始化设备") + async def initialize(self) -> bool: + self.logger.debug("initialize called, instrument=%s", self._instrument) + if self._instrument is not None: + self.data["status"] = "Idle" + self.logger.debug("设备已在 initialize 前连接") + return True + if propar is None: + self.data["status"] = "Offline" + return False + try: + self._instrument = propar.instrument( + self._port, + self._address, + baudrate=self._baudrate, + ) + unit = self._instrument.readParameter(129) + if unit is not None: + self.data["capacity_unit"] = str(unit) + tag = self._instrument.readParameter(115) + if tag is not None: + self.data["user_tag"] = str(tag) + self._poll_values() + self.data["status"] = "Idle" + self.logger.info("Bronkhorst MFC 连接成功") + return True + except Exception as e: + self.logger.error(f"连接失败: {e}") + self.data["status"] = "Offline" + return False + + @action(description="清理资源") + async def cleanup(self) -> bool: + try: + if self._instrument is not None: + try: + self._instrument.writeParameter(206, 0.0) + except Exception: + pass + self._instrument = None + self.data["status"] = "Offline" + return True + except Exception as e: + self.data["status"] = "Offline" + return False + + def _poll_values(self): + if self._instrument is None: + return + try: + flow_val = self._instrument.readParameter(205) + if flow_val is not None: + self.data["flow"] = float(flow_val) + self.data["value"] = float(flow_val) + sp_val = self._instrument.readParameter(206) + if sp_val is not None: + self.data["setpoint"] = float(sp_val) + temp_val = self._instrument.readParameter(142) + if temp_val is not None: + self.data["temperature"] = float(temp_val) + sp = self.data["setpoint"] + fl = self.data["flow"] + if sp > 0: + self.data["level"] = abs(fl - sp) / sp * 100.0 <= self._threshold_pct + else: + self.data["level"] = abs(fl) < 0.01 + except Exception as e: + self.logger.warning(f"读取设备数据失败: {e}") + + @action(description="读取流量值") + async def read_value(self, **kwargs) -> Dict[str, Any]: + self.data["status"] = "Busy" + try: + self._poll_values() + self.data["status"] = "Idle" + return { + "success": True, + "value": self.data["flow"], + "unit": self.data["capacity_unit"], + "setpoint": self.data["setpoint"], + "temperature": self.data["temperature"], + } + except Exception as e: + self.data["status"] = "Idle" + return {"success": False, "message": str(e)} + + @action(description="设置阈值百分比") + async def set_threshold(self, threshold: float, **kwargs) -> bool: + self._threshold_pct = float(threshold) + self._poll_values() + return True + + @action(description="设置流量设定值") + async def set_setpoint(self, setpoint: float, **kwargs) -> bool: + setpoint = float(setpoint) + if self._instrument is None: + self.logger.error("设备未连接") + return False + self.data["status"] = "Busy" + try: + self._instrument.writeParameter(206, setpoint) + self.data["setpoint"] = setpoint + await self._sleep(0.5) + self._poll_values() + self.data["status"] = "Idle" + return True + except Exception as e: + self.logger.error(f"set_setpoint 失败: {e}") + self.data["status"] = "Idle" + return False + + @action(description="停止流量输出") + async def stop(self, **kwargs) -> bool: + return await self.set_setpoint(0.0) + + @action(description="按百分比设置设定值") + async def set_setpoint_percent(self, percent: float, **kwargs) -> bool: + percent = float(percent) + if self._instrument is None: + return False + self.data["status"] = "Busy" + try: + raw_value = int(percent / 100.0 * 32000) + raw_value = max(0, min(32000, raw_value)) + self._instrument.setpoint = raw_value + await self._sleep(0.5) + self._poll_values() + self.data["status"] = "Idle" + return True + except Exception as e: + self.data["status"] = "Idle" + return False + + @action(description="设置用户标签") + async def set_user_tag(self, tag: str, **kwargs) -> bool: + tag = str(tag)[:12] + if self._instrument is None: + return False + try: + self._instrument.writeParameter(115, tag) + self.data["user_tag"] = tag + return True + except Exception as e: + return False + + @property + @topic_config() + def status(self) -> str: + return self.data.get("status", "Idle") + + @property + @topic_config() + def flow(self) -> float: + return self.data.get("flow", 0.0) + + @property + @topic_config() + def setpoint(self) -> float: + return self.data.get("setpoint", 0.0) + + @property + @topic_config() + def temperature(self) -> float: + return self.data.get("temperature", 0.0) + + @property + @topic_config() + def valve_output(self) -> float: + return self.data.get("valve_output", 0.0) + + @property + @topic_config() + def capacity_unit(self) -> str: + return self.data.get("capacity_unit", "") + + @property + @topic_config() + def user_tag(self) -> str: + return self.data.get("user_tag", "") + + @property + @topic_config() + def level(self) -> bool: + return self.data.get("level", False) + + @property + @topic_config() + def rssi(self) -> float: + return float(self.data.get("rssi", 0)) + + @property + @topic_config() + def value(self) -> float: + return self.data.get("value", 0.0) \ No newline at end of file diff --git a/device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.yaml b/device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.yaml new file mode 100644 index 0000000..35b00f2 --- /dev/null +++ b/device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.yaml @@ -0,0 +1,276 @@ +bronkhorst_el_flow: + category: + - sensor + - bronkhorst_el_flow + class: + action_value_mappings: + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-read_value: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: read_value的参数schema + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: read_value参数 + type: object + type: UniLabJsonCommandAsync + auto-set_setpoint: + feedback: {} + goal: {} + goal_default: + setpoint: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: set_setpoint的参数schema + properties: + feedback: {} + goal: + properties: + setpoint: + type: number + required: + - setpoint + type: object + result: {} + required: + - goal + title: set_setpoint参数 + type: object + type: UniLabJsonCommandAsync + auto-set_setpoint_percent: + feedback: {} + goal: {} + goal_default: + percent: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: set_setpoint_percent的参数schema + properties: + feedback: {} + goal: + properties: + percent: + type: number + required: + - percent + type: object + result: {} + required: + - goal + title: set_setpoint_percent参数 + type: object + type: UniLabJsonCommandAsync + auto-set_threshold: + feedback: {} + goal: {} + goal_default: + threshold: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: set_threshold的参数schema + properties: + feedback: {} + goal: + properties: + threshold: + type: number + required: + - threshold + type: object + result: {} + required: + - goal + title: set_threshold参数 + type: object + type: UniLabJsonCommandAsync + auto-set_user_tag: + feedback: {} + goal: {} + goal_default: + tag: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: set_user_tag的参数schema + properties: + feedback: {} + goal: + properties: + tag: + type: string + required: + - tag + type: object + result: {} + required: + - goal + title: set_user_tag参数 + type: object + type: UniLabJsonCommandAsync + auto-stop: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: stop的参数schema + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: stop参数 + type: object + type: UniLabJsonCommandAsync + module: device_package_example.devices.bronkhorst_el_flow.bronkhorst_el_flow:BronkhorstElFlow + status_types: + capacity_unit: str + flow: float + level: bool + rssi: int + setpoint: float + status: str + temperature: float + user_tag: str + value: float + valve_output: float + type: python + config_info: [] + description: Bronkhorst EL-FLOW Prestige 质量流量控制器(MFC),通过RS232/RS485 ProPar协议通信,支持流量测量、设定点控制、温度监测和阀门输出监控。适用于气体流量精密控制的实验室自动化应用。 + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + capacity_unit: + type: string + flow: + type: number + level: + type: boolean + rssi: + type: integer + setpoint: + type: number + status: + type: string + temperature: + type: number + user_tag: + type: string + value: + type: number + valve_output: + type: number + required: + - status + - flow + - setpoint + - temperature + - valve_output + - capacity_unit + - user_tag + - level + - rssi + - value + type: object + version: 1.0.0 diff --git a/device_package_example/devices/bronkhorst_el_flow/graph_example_bronkhorst_el_flow.json b/device_package_example/devices/bronkhorst_el_flow/graph_example_bronkhorst_el_flow.json new file mode 100644 index 0000000..c2cedbc --- /dev/null +++ b/device_package_example/devices/bronkhorst_el_flow/graph_example_bronkhorst_el_flow.json @@ -0,0 +1,21 @@ +{ + "nodes": [ + { + "id": "bronkhorst_mfc_1", + "name": "Bronkhorst EL-FLOW Prestige MFC", + "children": [], + "parent": null, + "type": "device", + "class": "bronkhorst_el_flow", + "position": {"x": 200, "y": 200, "z": 0}, + "config": { + "port": "COM12", + "baudrate": 38400, + "address": 3, + "channel": 1, + "threshold": 2.0 + }, + "data": {} + } + ] +} \ No newline at end of file diff --git a/device_package_example/devices/chi760e/chi760e.py b/device_package_example/devices/chi760e/chi760e.py new file mode 100644 index 0000000..a19d607 --- /dev/null +++ b/device_package_example/devices/chi760e/chi760e.py @@ -0,0 +1,775 @@ +""" +辰华 CHI760E 电化学工作站驱动 +基于 hardpotato 开源项目的宏命令(Macro)控制方案 + +控制链路: + Python → 生成 .mcr 宏命令文件 → subprocess 启动 chi760e.exe /runmacro → 读取 .txt 数据文件 + +支持技术:CV / LSV / CA / OCP / NPV / EIS + +参考: + - hardpotato: https://github.com/jrlLAB/hardpotato + - CHI Macro 格式: c\\x02\\0\\0\\n 头部 + 参数行 + run + save + forcequit +""" + +import logging +import os +import json +import time as time_module +import subprocess +from datetime import datetime +from typing import Dict, Any, Optional + +try: + import numpy as np +except ImportError: + np = None + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="chi760e", + category=["sensor", "chi760e"], + description="辰华 CHI760E 电化学工作站", + display_name="CHI760E 电化学工作站", +) +class CHI760E: + """辰华 CHI760E 电化学工作站 + + 通过 CHI 软件的宏命令(Macro)机制控制仪器。 + 每次实验:生成 .mcr → subprocess 调用 chi760e.exe /runmacro → 等待完成 → 解析数据文件。 + """ + + _ros_node: "BaseROS2DeviceNode" + + # ==================== 初始化 ==================== + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and 'id' in kwargs: + device_id = kwargs.pop('id') + if config is None and 'config' in kwargs: + config = kwargs.pop('config') + + self.device_id = device_id or "chi760e" + self.config = config or {} + self.logger = logging.getLogger(f"CHI760E.{self.device_id}") + + # self.data 预填充所有 @property 字段 + self.data = { + "status": "Idle", + "technique": "", + "last_data_file": "", + "last_experiment_time": "", + "data_folder": "", + } + + # 配置参数(从 config 和 kwargs 双重读取) + self._chi_exe_path = ( + self.config.get("chi_exe_path") + or kwargs.get("chi_exe_path", "") + ) + self._data_folder = ( + self.config.get("data_folder") + or kwargs.get("data_folder", "") + ) + self._default_sens = float( + self.config.get("default_sens") + or kwargs.get("default_sens", 1e-6) + ) + + self.data["data_folder"] = self._data_folder + + @not_action + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + @action() + async def initialize(self) -> bool: + """初始化:验证 CHI 软件路径和数据目录""" + # 验证 CHI 软件路径 + if not self._chi_exe_path: + self.logger.error("chi_exe_path not configured") + self.data["status"] = "Error" + return False + + if not os.path.isfile(self._chi_exe_path): + self.logger.error(f"CHI software not found: {self._chi_exe_path}") + self.data["status"] = "Error" + return False + + # 创建数据目录 + if self._data_folder: + os.makedirs(self._data_folder, exist_ok=True) + else: + self.logger.error("data_folder not configured") + self.data["status"] = "Error" + return False + + self.data["status"] = "Idle" + self.logger.info( + f"Initialized: exe={self._chi_exe_path}, data={self._data_folder}" + ) + return True + + @action() + async def cleanup(self) -> bool: + """清理""" + self.data["status"] = "Offline" + self.logger.info("Cleanup complete") + return True + + # ==================== 宏命令核心 ==================== + + def _generate_macro_header(self, header_text: str) -> str: + """生成 CHI 宏命令文件头部(与 hardpotato 完全一致)""" + folder = self._data_folder.replace("\\", "/") + head = ( + "c\x02\0\0\n" + f"folder: {folder}\n" + "fileoverride\n" + f"header: {header_text}\n\n" + ) + return head + + def _generate_macro_footer(self, file_name: str) -> str: + """生成宏命令文件尾部""" + foot = ( + f"\nrun\n" + f"save:{file_name}\n" + f"tsave:{file_name}\n" + " forcequit: yesiamsure\n" + ) + return foot + + def _write_macro(self, macro_text: str, file_name: str) -> str: + """写入 .mcr 宏命令文件,返回文件完整路径""" + mcr_path = os.path.join(self._data_folder, f"{file_name}.mcr") + with open(mcr_path, "wb") as f: + f.write(macro_text.encode("ascii")) + self.logger.debug(f"Macro written: {mcr_path}") + return mcr_path + + def _run_macro(self, mcr_path: str) -> bool: + """调用 CHI 软件执行宏命令(阻塞等待完成)""" + exe = self._chi_exe_path.replace("\\", "/") + mcr = mcr_path.replace("\\", "/") + command = f'"{exe}" /runmacro:"{mcr}"' + self.logger.info(f"Executing: {command}") + try: + result = subprocess.run( + command, + shell=True, + timeout=3600, # 最长 1 小时 + capture_output=True, + ) + self.logger.info(f"CHI exited with code {result.returncode}") + return True + except subprocess.TimeoutExpired: + self.logger.error("CHI software execution timed out (1h)") + return False + except Exception as e: + self.logger.error(f"Failed to execute CHI software: {e}") + return False + + def _save_metadata(self, file_name: str, technique: str, params: dict): + """保存实验元数据 JSON""" + meta = { + "device_id": self.device_id, + "technique": technique, + "timestamp": datetime.now().isoformat(), + "parameters": params, + "data_file": f"{file_name}.txt", + "macro_file": f"{file_name}.mcr", + } + meta_path = os.path.join(self._data_folder, f"{file_name}_meta.json") + with open(meta_path, "w", encoding="utf-8") as f: + json.dump(meta, f, indent=2, ensure_ascii=False) + self.logger.debug(f"Metadata saved: {meta_path}") + + def _parse_data_file(self, file_name: str, search_text: str) -> dict: + """解析 CHI 输出的 .txt 数据文件 + + CHI 数据文件格式: + - 头部包含实验参数 + - 数据起始行包含 search_text(如 "Potential/V," 或 "Time/sec,") + - 数据行为 CSV 格式 + """ + file_path = os.path.join(self._data_folder, f"{file_name}.txt") + if not os.path.isfile(file_path): + self.logger.warning(f"Data file not found: {file_path}") + return {"raw_file": file_path, "data": []} + + result = {"raw_file": file_path, "header_lines": [], "data": []} + + try: + with open(file_path, "r", encoding="utf-8", errors="ignore") as f: + lines = f.readlines() + + # 找到数据起始行 + skip_rows = 0 + for i, line in enumerate(lines): + if search_text in line: + skip_rows = i + 1 + break + + # 保存 header + result["header_lines"] = [l.strip() for l in lines[:skip_rows]] + + # 解析数据 + if np is not None and skip_rows > 0: + try: + data = np.loadtxt(file_path, delimiter=",", skiprows=skip_rows) + result["data"] = data.tolist() + result["shape"] = list(data.shape) + except Exception as e: + self.logger.warning(f"numpy loadtxt failed: {e}") + # 回退到手动解析 + for line in lines[skip_rows:]: + line = line.strip() + if line and not line.startswith("#"): + parts = line.split(",") + try: + row = [float(x) for x in parts if x.strip()] + result["data"].append(row) + except ValueError: + continue + else: + # 无 numpy 时手动解析 + for line in lines[skip_rows:]: + line = line.strip() + if line and not line.startswith("#"): + parts = line.split(",") + try: + row = [float(x) for x in parts if x.strip()] + result["data"].append(row) + except ValueError: + continue + + except Exception as e: + self.logger.error(f"Failed to parse data file: {e}") + + return result + + def _generate_timestamp_filename(self, technique: str) -> str: + """生成带时间戳的文件名""" + ts = datetime.now().strftime("%Y%m%d_%H%M%S") + return f"{technique}_{ts}" + + # ==================== 电化学技术 ==================== + + @action() + async def run_cv(self, ei: float = -0.2, ev1: float = 0.2, ev2: float = -0.2, + ef: float = -0.2, sr: float = 0.1, de: float = 0.001, + n_sweeps: float = 2.0, sens: float = 0.0, + qt: float = 2.0, resistance: float = 0.0, + **kwargs) -> str: + """运行循环伏安法 (Cyclic Voltammetry) + + Args: + ei: 初始电位 (V) + ev1: 第一顶点电位 (V) + ev2: 第二顶点电位 (V) + ef: 终止电位 (V) + sr: 扫描速率 (V/s) + de: 采样间隔 (V) + n_sweeps: 扫描圈数 + sens: 灵敏度 (A/V),0 则使用默认值 + qt: 静置时间 (s) + resistance: 溶液电阻 (Ω),用于 IR 补偿,0 为不补偿 + Returns: + 数据文件路径 + """ + self.data["status"] = "Busy" + self.data["technique"] = "CV" + + if sens == 0.0: + sens = self._default_sens + n_sweeps_int = int(n_sweeps) + 1 # CHI 的 final E 默认开启,需 +1 + + # 确定扫描方向 + if ev1 > ev2: + eh, el, pn = ev1, ev2, "p" + else: + eh, el, pn = ev2, ev1, "n" + + file_name = self._generate_timestamp_filename("CV") + header = f"CV ei={ei} ev1={ev1} ev2={ev2} ef={ef} sr={sr}" + + # 构建宏命令 + head = self._generate_macro_header(header) + body = ( + f"tech=cv\n" + f"ei={ei}\n" + f"eh={eh}\n" + f"el={el}\n" + f"pn={pn}\n" + f"cl={n_sweeps_int}\n" + f"efon\n" + f"ef={ef}\n" + f"si={de}\n" + f"qt={qt}\n" + f"v={sr}\n" + f"sens={sens}" + ) + if resistance: + body += f"\nmir={resistance}\nircompon" + foot_extra = "\nircompoff" + else: + foot_extra = "" + foot = ( + f"\nrun" + f"{foot_extra}\n" + f"save:{file_name}\n" + f"tsave:{file_name}\n" + f" forcequit: yesiamsure\n" + ) + macro_text = head + body + foot + + # 执行 + mcr_path = self._write_macro(macro_text, file_name) + params = dict(ei=ei, ev1=ev1, ev2=ev2, ef=ef, sr=sr, de=de, + n_sweeps=int(n_sweeps), sens=sens, qt=qt, resistance=resistance) + self._save_metadata(file_name, "CV", params) + + success = self._run_macro(mcr_path) + + data_file = os.path.join(self._data_folder, f"{file_name}.txt") + self.data["last_data_file"] = data_file + self.data["last_experiment_time"] = datetime.now().isoformat() + self.data["status"] = "Idle" if success else "Error" + + self.logger.info(f"CV completed: {data_file}") + return data_file + + @action() + async def run_lsv(self, ei: float = -0.2, ef: float = 0.2, + sr: float = 0.1, de: float = 0.001, + sens: float = 0.0, qt: float = 2.0, + resistance: float = 0.0, + **kwargs) -> str: + """运行线性扫描伏安法 (Linear Sweep Voltammetry) + + Args: + ei: 初始电位 (V) + ef: 终止电位 (V) + sr: 扫描速率 (V/s) + de: 采样间隔 (V) + sens: 灵敏度 (A/V) + qt: 静置时间 (s) + resistance: 溶液电阻 (Ω) + Returns: + 数据文件路径 + """ + self.data["status"] = "Busy" + self.data["technique"] = "LSV" + + if sens == 0.0: + sens = self._default_sens + + file_name = self._generate_timestamp_filename("LSV") + header = f"LSV ei={ei} ef={ef} sr={sr}" + + head = self._generate_macro_header(header) + body = ( + f"tech=lsv\n" + f"ei={ei}\n" + f"ef={ef}\n" + f"v={sr}\n" + f"si={de}\n" + f"qt={qt}\n" + f"sens={sens}" + ) + if resistance: + body += f"\nmir={resistance}\nircompon" + foot_extra = "\nircompoff" + else: + foot_extra = "" + foot = ( + f"\nrun" + f"{foot_extra}\n" + f"save:{file_name}\n" + f"tsave:{file_name}\n" + f" forcequit: yesiamsure\n" + ) + macro_text = head + body + foot + + mcr_path = self._write_macro(macro_text, file_name) + params = dict(ei=ei, ef=ef, sr=sr, de=de, sens=sens, qt=qt, resistance=resistance) + self._save_metadata(file_name, "LSV", params) + + success = self._run_macro(mcr_path) + + data_file = os.path.join(self._data_folder, f"{file_name}.txt") + self.data["last_data_file"] = data_file + self.data["last_experiment_time"] = datetime.now().isoformat() + self.data["status"] = "Idle" if success else "Error" + + self.logger.info(f"LSV completed: {data_file}") + return data_file + + @action() + async def run_ca(self, ei: float = 0.2, dt: float = 0.001, + ttot: float = 2.0, sens: float = 0.0, + qt: float = 2.0, resistance: float = 0.0, + **kwargs) -> str: + """运行计时安培法 (Chronoamperometry) + + Args: + ei: 阶跃电位 (V) + dt: 采样间隔 (s) + ttot: 总时间 (s) + sens: 灵敏度 (A/V) + qt: 静置时间 (s) + resistance: 溶液电阻 (Ω) + Returns: + 数据文件路径 + """ + self.data["status"] = "Busy" + self.data["technique"] = "CA" + + if sens == 0.0: + sens = self._default_sens + + file_name = self._generate_timestamp_filename("CA") + header = f"CA ei={ei} ttot={ttot}" + + head = self._generate_macro_header(header) + body = ( + f"tech=i-t\n" + f"ei={ei}\n" + f"st={ttot}\n" + f"si={dt}\n" + f"qt={qt}\n" + f"sens={sens}" + ) + if resistance: + body += f"\nmir={resistance}\nircompon" + foot_extra = "\nircompoff" + else: + foot_extra = "" + foot = ( + f"\nrun" + f"{foot_extra}\n" + f"save:{file_name}\n" + f"tsave:{file_name}\n" + f" forcequit: yesiamsure\n" + ) + macro_text = head + body + foot + + mcr_path = self._write_macro(macro_text, file_name) + params = dict(ei=ei, dt=dt, ttot=ttot, sens=sens, qt=qt, resistance=resistance) + self._save_metadata(file_name, "CA", params) + + success = self._run_macro(mcr_path) + + data_file = os.path.join(self._data_folder, f"{file_name}.txt") + self.data["last_data_file"] = data_file + self.data["last_experiment_time"] = datetime.now().isoformat() + self.data["status"] = "Idle" if success else "Error" + + self.logger.info(f"CA completed: {data_file}") + return data_file + + @action() + async def run_ocp(self, ttot: float = 10.0, dt: float = 0.01, + qt: float = 2.0, + **kwargs) -> str: + """运行开路电位 (Open Circuit Potential) + + Args: + ttot: 总时间 (s) + dt: 采样间隔 (s) + qt: 静置时间 (s) + Returns: + 数据文件路径 + """ + self.data["status"] = "Busy" + self.data["technique"] = "OCP" + + file_name = self._generate_timestamp_filename("OCP") + header = f"OCP ttot={ttot}" + + head = self._generate_macro_header(header) + body = ( + f"tech=ocpt\n" + f"st={ttot}\n" + f"eh=10\n" + f"el=-10\n" + f"si={dt}\n" + f"qt={qt}" + ) + foot = ( + f"\nrun\n" + f"save:{file_name}\n" + f"tsave:{file_name}\n" + f"forcequit: yesiamsure\n" + ) + macro_text = head + body + foot + + mcr_path = self._write_macro(macro_text, file_name) + params = dict(ttot=ttot, dt=dt, qt=qt) + self._save_metadata(file_name, "OCP", params) + + success = self._run_macro(mcr_path) + + data_file = os.path.join(self._data_folder, f"{file_name}.txt") + self.data["last_data_file"] = data_file + self.data["last_experiment_time"] = datetime.now().isoformat() + self.data["status"] = "Idle" if success else "Error" + + self.logger.info(f"OCP completed: {data_file}") + return data_file + + @action() + async def run_npv(self, ei: float = 0.5, ef: float = -0.5, + de: float = 0.01, pw: float = 0.1, + sw: float = 0.05, prod: float = 10.0, + sens: float = 0.0, qt: float = 2.0, + **kwargs) -> str: + """运行常规脉冲伏安法 (Normal Pulse Voltammetry) + + Args: + ei: 初始电位 (V) + ef: 终止电位 (V) + de: 电位增量 (V) + pw: 脉冲宽度 (s) + sw: 采样宽度 (s) + prod: 脉冲周期 (s) + sens: 灵敏度 (A/V) + qt: 静置时间 (s) + Returns: + 数据文件路径 + """ + self.data["status"] = "Busy" + self.data["technique"] = "NPV" + + if sens == 0.0: + sens = self._default_sens + + file_name = self._generate_timestamp_filename("NPV") + header = f"NPV ei={ei} ef={ef}" + + head = self._generate_macro_header(header) + body = ( + f"tech=NPV\n" + f"ei={ei}\n" + f"ef={ef}\n" + f"incre={de}\n" + f"pw={pw}\n" + f"sw={sw}\n" + f"prod={prod}\n" + f"qt={qt}\n" + f"sens={sens}" + ) + foot = ( + f"\nrun\n" + f"save:{file_name}\n" + f"tsave:{file_name}\n" + f" forcequit: yesiamsure\n" + ) + macro_text = head + body + foot + + mcr_path = self._write_macro(macro_text, file_name) + params = dict(ei=ei, ef=ef, de=de, pw=pw, sw=sw, prod=prod, sens=sens, qt=qt) + self._save_metadata(file_name, "NPV", params) + + success = self._run_macro(mcr_path) + + data_file = os.path.join(self._data_folder, f"{file_name}.txt") + self.data["last_data_file"] = data_file + self.data["last_experiment_time"] = datetime.now().isoformat() + self.data["status"] = "Idle" if success else "Error" + + self.logger.info(f"NPV completed: {data_file}") + return data_file + + @action() + async def run_eis(self, ei: float = 0.0, fl: float = 1.0, + fh: float = 100000.0, amp: float = 0.01, + sens: float = 0.0, qt: float = 2.0, + **kwargs) -> str: + """运行电化学阻抗谱 (Electrochemical Impedance Spectroscopy) + + Args: + ei: 直流偏置电位 (V) + fl: 最低频率 (Hz) + fh: 最高频率 (Hz) + amp: 交流振幅 (V) + sens: 灵敏度 (A/V) + qt: 静置时间 (s) + Returns: + 数据文件路径 + """ + self.data["status"] = "Busy" + self.data["technique"] = "EIS" + + if sens == 0.0: + sens = self._default_sens + + file_name = self._generate_timestamp_filename("EIS") + header = f"EIS ei={ei} fl={fl} fh={fh} amp={amp}" + + head = self._generate_macro_header(header) + body = ( + f"tech=imp\n" + f"ei={ei}\n" + f"fl={fl}\n" + f"fh={fh}\n" + f"amp={amp}\n" + f"sens={sens}\n" + f"qt={qt}" + ) + foot = ( + f"\nrun\n" + f"save:{file_name}\n" + f"tsave:{file_name}\n" + f"forcequit: yesiamsure\n" + ) + macro_text = head + body + foot + + mcr_path = self._write_macro(macro_text, file_name) + params = dict(ei=ei, fl=fl, fh=fh, amp=amp, sens=sens, qt=qt) + self._save_metadata(file_name, "EIS", params) + + success = self._run_macro(mcr_path) + + data_file = os.path.join(self._data_folder, f"{file_name}.txt") + self.data["last_data_file"] = data_file + self.data["last_experiment_time"] = datetime.now().isoformat() + self.data["status"] = "Idle" if success else "Error" + + self.logger.info(f"EIS completed: {data_file}") + return data_file + + # ==================== 通用动作 ==================== + + @action() + async def stop_operation(self, **kwargs) -> bool: + """终止当前实验 + + 注意:CHI 宏命令模式下无法直接中止正在运行的实验。 + 此方法通过 taskkill 强制结束 CHI 软件进程。 + """ + try: + exe_name = os.path.basename(self._chi_exe_path) + subprocess.run( + f'taskkill /f /im "{exe_name}"', + shell=True, + capture_output=True, + ) + self.logger.warning("Force-killed CHI software process") + except Exception as e: + self.logger.error(f"Failed to stop: {e}") + return False + + self.data["status"] = "Idle" + return True + + @action() + async def list_data_files(self, **kwargs) -> str: + """列出数据目录下所有 .txt 数据文件 + + Returns: + 文件列表的 JSON 字符串 + """ + if not self._data_folder or not os.path.isdir(self._data_folder): + return "[]" + files = sorted([ + f for f in os.listdir(self._data_folder) + if f.endswith(".txt") and not f.endswith("_meta.json") + ]) + return json.dumps(files, ensure_ascii=False) + + @action() + async def read_data(self, file_name: str = "", **kwargs) -> str: + """读取并解析指定数据文件 + + Args: + file_name: 文件名(不含路径),留空则读取最后一次实验 + Returns: + JSON 格式的解析结果 + """ + if not file_name: + file_name = os.path.basename(self.data.get("last_data_file", "")) + if not file_name: + return json.dumps({"error": "No data file specified"}) + + # 去掉 .txt 后缀 + base_name = file_name.replace(".txt", "") + + # 根据文件名前缀判断数据格式 + tech_prefix = base_name.split("_")[0].upper() + if tech_prefix in ("CV", "LSV"): + search_text = "Potential/V," + elif tech_prefix in ("CA", "OCP"): + search_text = "Time/sec," + elif tech_prefix == "NPV": + search_text = "Potential/V," + elif tech_prefix == "EIS": + search_text = "Freq/Hz," # EIS 可能用 Freq 开头 + else: + search_text = "Potential/V," + + result = self._parse_data_file(base_name, search_text) + # 如果第一种 search_text 没找到,用备选 + if not result["data"] and search_text != "Time/sec,": + result = self._parse_data_file(base_name, "Time/sec,") + if not result["data"]: + result = self._parse_data_file(base_name, "Z'/ohm,") + + return json.dumps(result, ensure_ascii=False) + + # ==================== 属性(@property)==================== + + @property + @topic_config() + def status(self) -> str: + """设备状态: Idle / Busy / Error / Offline""" + return self.data.get("status", "Idle") + + @property + @topic_config() + def technique(self) -> str: + """当前/上一次执行的电化学技术""" + return self.data.get("technique", "") + + @property + @topic_config() + def last_data_file(self) -> str: + """最后一次实验的数据文件路径""" + return self.data.get("last_data_file", "") + + @property + @topic_config() + def last_experiment_time(self) -> str: + """最后一次实验的时间""" + return self.data.get("last_experiment_time", "") + + @property + @topic_config() + def data_folder(self) -> str: + """数据保存目录""" + return self.data.get("data_folder", "") diff --git a/device_package_example/devices/chi760e/chi760e.yaml b/device_package_example/devices/chi760e/chi760e.yaml new file mode 100644 index 0000000..8d333f4 --- /dev/null +++ b/device_package_example/devices/chi760e/chi760e.yaml @@ -0,0 +1,467 @@ +chi760e: + category: + - sensor + - chi760e + class: + action_value_mappings: + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-list_data_files: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: list_data_files参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-read_data: + feedback: {} + goal: {} + goal_default: + file_name: '' + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + file_name: + default: '' + type: string + required: [] + type: object + result: {} + required: + - goal + title: read_data参数 + type: object + type: UniLabJsonCommandAsync + auto-run_ca: + feedback: {} + goal: {} + goal_default: + dt: 0.001 + ei: 0.2 + qt: 2.0 + resistance: 0.0 + sens: 0.0 + ttot: 2.0 + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + dt: + default: 0.001 + type: number + ei: + default: 0.2 + type: number + qt: + default: 2.0 + type: number + resistance: + default: 0.0 + type: number + sens: + default: 0.0 + type: number + ttot: + default: 2.0 + type: number + required: [] + type: object + result: {} + required: + - goal + title: run_ca参数 + type: object + type: UniLabJsonCommandAsync + auto-run_cv: + feedback: {} + goal: {} + goal_default: + de: 0.001 + ef: -0.2 + ei: -0.2 + ev1: 0.2 + ev2: -0.2 + n_sweeps: 2.0 + qt: 2.0 + resistance: 0.0 + sens: 0.0 + sr: 0.1 + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + de: + default: 0.001 + type: number + ef: + default: -0.2 + type: number + ei: + default: -0.2 + type: number + ev1: + default: 0.2 + type: number + ev2: + default: -0.2 + type: number + n_sweeps: + default: 2.0 + type: number + qt: + default: 2.0 + type: number + resistance: + default: 0.0 + type: number + sens: + default: 0.0 + type: number + sr: + default: 0.1 + type: number + required: [] + type: object + result: {} + required: + - goal + title: run_cv参数 + type: object + type: UniLabJsonCommandAsync + auto-run_eis: + feedback: {} + goal: {} + goal_default: + amp: 0.01 + ei: 0.0 + fh: 100000.0 + fl: 1.0 + qt: 2.0 + sens: 0.0 + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + amp: + default: 0.01 + type: number + ei: + default: 0.0 + type: number + fh: + default: 100000.0 + type: number + fl: + default: 1.0 + type: number + qt: + default: 2.0 + type: number + sens: + default: 0.0 + type: number + required: [] + type: object + result: {} + required: + - goal + title: run_eis参数 + type: object + type: UniLabJsonCommandAsync + auto-run_lsv: + feedback: {} + goal: {} + goal_default: + de: 0.001 + ef: 0.2 + ei: -0.2 + qt: 2.0 + resistance: 0.0 + sens: 0.0 + sr: 0.1 + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + de: + default: 0.001 + type: number + ef: + default: 0.2 + type: number + ei: + default: -0.2 + type: number + qt: + default: 2.0 + type: number + resistance: + default: 0.0 + type: number + sens: + default: 0.0 + type: number + sr: + default: 0.1 + type: number + required: [] + type: object + result: {} + required: + - goal + title: run_lsv参数 + type: object + type: UniLabJsonCommandAsync + auto-run_npv: + feedback: {} + goal: {} + goal_default: + de: 0.01 + ef: -0.5 + ei: 0.5 + prod: 10.0 + pw: 0.1 + qt: 2.0 + sens: 0.0 + sw: 0.05 + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + de: + default: 0.01 + type: number + ef: + default: -0.5 + type: number + ei: + default: 0.5 + type: number + prod: + default: 10.0 + type: number + pw: + default: 0.1 + type: number + qt: + default: 2.0 + type: number + sens: + default: 0.0 + type: number + sw: + default: 0.05 + type: number + required: [] + type: object + result: {} + required: + - goal + title: run_npv参数 + type: object + type: UniLabJsonCommandAsync + auto-run_ocp: + feedback: {} + goal: {} + goal_default: + dt: 0.01 + qt: 2.0 + ttot: 10.0 + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + dt: + default: 0.01 + type: number + qt: + default: 2.0 + type: number + ttot: + default: 10.0 + type: number + required: [] + type: object + result: {} + required: + - goal + title: run_ocp参数 + type: object + type: UniLabJsonCommandAsync + auto-stop_operation: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: stop_operation参数 + type: object + type: UniLabJsonCommandAsync + module: device_package_example.devices.chi760e.chi760e:CHI760E + status_types: + data_folder: str + last_data_file: str + last_experiment_time: str + status: str + technique: str + type: python + config_info: [] + description: 辰华 CHI760E 电化学工作站 (通过 CHI 软件宏命令控制) + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + data_folder: + type: string + last_data_file: + type: string + last_experiment_time: + type: string + status: + type: string + technique: + type: string + required: + - status + - technique + - last_data_file + - last_experiment_time + - data_folder + type: object + version: 1.0.0 diff --git a/device_package_example/devices/chi760e/graph_example_chi760e.json b/device_package_example/devices/chi760e/graph_example_chi760e.json new file mode 100644 index 0000000..57a1794 --- /dev/null +++ b/device_package_example/devices/chi760e/graph_example_chi760e.json @@ -0,0 +1,19 @@ +{ + "nodes": [ + { + "id": "chi760e_1", + "name": "辰华CHI760E电化学工作站", + "children": [], + "parent": null, + "type": "device", + "class": "chi760e", + "position": {"x": 300, "y": 300, "z": 0}, + "config": { + "chi_exe_path": "C:/Users/lsd/Desktop/chi760e/chi760e.exe", + "data_folder": "C:/Users/lsd/Desktop/chi760e_data", + "default_sens": 1e-6 + }, + "data": {} + } + ] +} diff --git a/device_package_example/devices/cmos_detector/cmos_detector.py b/device_package_example/devices/cmos_detector/cmos_detector.py new file mode 100644 index 0000000..bb68515 --- /dev/null +++ b/device_package_example/devices/cmos_detector/cmos_detector.py @@ -0,0 +1,810 @@ +import logging +import time as time_module +import os +import json +import csv +from datetime import datetime +from typing import Dict, Any, Optional, List + +try: + import serial +except ImportError: + serial = None + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="cmos_detector", + category=["cmos_detector"], + description="LCAMV8 CMOS 线阵检测器", + display_name="CMOS 线阵检测器", +) +class CMOSDetector: + """LCAMV8 CMOS 线阵检测器驱动 (S11639-01, 2048 pixels) + + 通讯协议: USB 虚拟串口, 115200 baud, 8N1 + 帧格式: [0x81][CMD][DATA1][DATA2][CRC], CRC = sum(byte0~3) & 0xFF + 特殊: 版本查询返回 ASCII 字符串, 采集数据返回 4103 字节大帧 + 注意: 单次采集(0x01)无响应, 必须用连续采集(0x02)+停止(0x06)实现单帧采集 + """ + + _ros_node: "BaseROS2DeviceNode" + + # ── 命令码 ── + CMD_SINGLE_ACQ = 0x01 # 单次采集 (实测无响应, 不使用) + CMD_CONTINUOUS_ACQ = 0x02 # 连续采集 + CMD_INTEGRATION_TIME = 0x03 # 设置积分时间 + CMD_GAIN = 0x04 # 设置增益 + CMD_OFFSET = 0x05 # 设置偏移 + CMD_STOP = 0x06 # 暂停采集 + CMD_TRIGGER_MODE = 0x07 # 触发模式 + CMD_TRIGGER_INTERVAL = 0x08 # 设置触发间隔 + CMD_GET_VERSION = 0x09 # 获取版本 (返回ASCII) + CMD_GET_INTEG_TIME = 0x0A # 获取积分时间 + CMD_GET_INTERVAL = 0x0B # 获取触发间隔 + CMD_AVG_COUNT = 0x0C # 设置平均次数 + CMD_ANALOG_OUT = 0x0D # 模拟电压输出 + CMD_GET_AVG_COUNT = 0x0E # 获取平均次数 + CMD_SYNC_OUTPUT = 0x0F # 同步信号输出 + CMD_TRIGGER_OUT2 = 0x10 # Trigger Out2 输出 + CMD_INTEG_UNIT = 0x11 # 积分时间单位设置 + CMD_GET_INTEG_UNIT = 0x12 # 获取积分时间单位 + CMD_TTL_BAUDRATE = 0x13 # TTL 串口波特率设置 + CMD_READ_X_COORD = 0x15 # 读取 X 坐标值 + CMD_GET_TTL_BAUD = 0x16 # 获取 TTL 串口波特率 + CMD_SAVE_PARAMS = 0x22 # 保存参数 + CMD_GET_GAIN = 0x23 # 获取增益 + CMD_GET_OFFSET = 0x24 # 获取偏移 + CMD_SET_SMOOTH = 0x25 # 设置平滑等级 + CMD_GET_SMOOTH = 0x26 # 获取平滑等级 + CMD_ERASE_FLASH = 0x27 # 擦除 Flash + CMD_WRITE_CORRECTION = 0x28 # 写入矫正系数 + CMD_READ_CORRECTION = 0x29 # 获取矫正系数 + + # ── 数据帧常量 ── + HEAD = 0x81 + PIXEL_COUNT = 2048 + DATA_FRAME_SIZE = 5 + PIXEL_COUNT * 2 + 2 # 4103 bytes + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and 'id' in kwargs: + device_id = kwargs.pop('id') + if config is None and 'config' in kwargs: + config = kwargs.pop('config') + self.device_id = device_id or "cmos_detector" + self.config = config or {} + self.logger = logging.getLogger(f"CMOSDetector.{self.device_id}") + + self._serial: Optional[serial.Serial] = None + self._is_acquiring = False + self._correction_coeffs = [None, None, None, None] # f[0]~f[3] 用于像素→波长转换 + self._wavelengths: List[float] = [] # 2048 个波长值 + self._last_pixel_data: List[int] = [] # 最近一帧原始像素值 + + # 注意: UniLab 框架只支持 float 和 str 类型的属性 + # 所有数值属性使用 float, 布尔使用 str ("true"/"false") + self.data = { + "status": "Idle", + "level": "false", + "value": "[]", + "integration_time": 10000.0, + "integration_time_unit": "ms", + "gain": 0.0, + "offset": 0.0, + "smooth_level": 1.0, + "average_count": 1.0, + "trigger_mode": 0.0, + "trigger_interval": 0.0, + "version_info": "", + } + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + # ══════════════════════════════════════════ + # 底层通信 + # ══════════════════════════════════════════ + + def _calc_crc(self, data: bytes) -> int: + """CRC = sum(byte0~byte3) & 0xFF""" + return sum(data) & 0xFF + + def _build_cmd(self, cmd: int, data1: int = 0x00, data2: int = 0x00) -> bytes: + """构建 5 字节命令帧""" + frame = bytes([self.HEAD, cmd, data1, data2]) + crc = self._calc_crc(frame) + return frame + bytes([crc]) + + def _send_cmd(self, cmd: int, data1: int = 0x00, data2: int = 0x00) -> bool: + """发送命令帧, 返回是否成功""" + if not self._serial or not self._serial.is_open: + self.logger.error("串口未打开") + return False + frame = self._build_cmd(cmd, data1, data2) + self.logger.debug(f"发送: {frame.hex()}") + self._serial.write(frame) + return True + + def _read_response_5byte(self, timeout: float = 1.0) -> Optional[bytes]: + """读取 5 字节标准响应帧, 先定位帧头 0x81""" + if not self._serial or not self._serial.is_open: + return None + old_timeout = self._serial.timeout + try: + self._serial.timeout = timeout + # 逐字节找帧头 + deadline = time_module.time() + timeout + while time_module.time() < deadline: + b = self._serial.read(1) + if not b: + return None + if b[0] == self.HEAD: + rest = self._serial.read(4) + if len(rest) == 4: + frame = b + rest + self.logger.debug(f"收到5字节帧: {frame.hex()}") + return frame + return None + return None + finally: + self._serial.timeout = old_timeout + + def _read_version_response(self, timeout: float = 2.0) -> Optional[str]: + """读取版本信息响应 (ASCII 字符串, 非二进制帧)""" + if not self._serial or not self._serial.is_open: + return None + old_timeout = self._serial.timeout + try: + self._serial.timeout = timeout + time_module.sleep(0.5) + n = self._serial.in_waiting + if n > 0: + data = self._serial.read(n) + try: + text = data.decode('ascii', errors='ignore') + self.logger.debug(f"版本信息: {text}") + return text + except Exception: + return data.hex() + return None + finally: + self._serial.timeout = old_timeout + + def _read_image_frame(self, timeout: float = 5.0) -> Optional[List[int]]: + """读取一帧图像数据 (4103 字节), 返回 2048 个像素值""" + if not self._serial or not self._serial.is_open: + return None + old_timeout = self._serial.timeout + try: + self._serial.timeout = timeout + # 找帧头 0x81 + deadline = time_module.time() + timeout + while time_module.time() < deadline: + b = self._serial.read(1) + if not b: + return None + if b[0] == self.HEAD: + # 读取剩余 4102 字节 + buf = bytearray(b) + while len(buf) < self.DATA_FRAME_SIZE and time_module.time() < deadline: + chunk = self._serial.read(self.DATA_FRAME_SIZE - len(buf)) + if not chunk: + break + buf.extend(chunk) + if len(buf) < self.DATA_FRAME_SIZE: + self.logger.warning(f"图像帧不完整: {len(buf)}/{self.DATA_FRAME_SIZE}") + return None + # 验证帧头: 81 01 ... + if buf[1] != 0x01: + self.logger.debug(f"非图像帧, CMD=0x{buf[1]:02X}, 继续查找") + continue + # 解析 2048 个像素值 (高位在前) + pixels = [] + for i in range(self.PIXEL_COUNT): + idx = 5 + i * 2 + val = (buf[idx] << 8) | buf[idx + 1] + pixels.append(val) + # 校验 CRC (数据部分累加和, 高低位) + data_sum = sum(buf[5:5 + self.PIXEL_COUNT * 2]) + crc_h = buf[-2] + crc_l = buf[-1] + expected_crc = (crc_h << 8) | crc_l + actual_crc = data_sum & 0xFFFF + if expected_crc != actual_crc: + self.logger.warning(f"CRC 校验失败: 期望 {expected_crc:#06x}, 实际 {actual_crc:#06x}") + return pixels + return None + finally: + self._serial.timeout = old_timeout + + async def _async_sleep(self, seconds: float): + """安全的异步休眠""" + try: + if hasattr(self, '_ros_node') and self._ros_node is not None: + await self._ros_node.sleep(seconds) + else: + time_module.sleep(seconds) + except Exception: + time_module.sleep(seconds) + + # ══════════════════════════════════════════ + # 生命周期 + # ══════════════════════════════════════════ + + @action() + async def initialize(self) -> bool: + """初始化: 打开串口, 读取版本信息和当前参数""" + if serial is None: + self.logger.error("pyserial 未安装") + self.data["status"] = "Offline" + return False + port = self.config.get("port", "COM10") + baudrate = self.config.get("baudrate", 115200) + + try: + self._serial = serial.Serial( + port=port, + baudrate=baudrate, + bytesize=serial.EIGHTBITS, + parity=serial.PARITY_NONE, + stopbits=serial.STOPBITS_ONE, + timeout=2 + ) + self.logger.info(f"串口 {port} 已打开") + except Exception as e: + self.logger.error(f"串口打开失败: {e}") + self.data["status"] = "Offline" + return False + + await self._async_sleep(0.3) + + # 读取版本信息 + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_GET_VERSION) + version = self._read_version_response(timeout=2.0) + if version: + self.data["version_info"] = version + self.logger.info(f"设备版本: {version}") + + await self._async_sleep(0.1) + + # 读取当前积分时间 + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_GET_INTEG_TIME) + resp = self._read_response_5byte(timeout=1.0) + if resp and len(resp) == 5: + self.data["integration_time"] = float((resp[2] << 8) | resp[3]) + + await self._async_sleep(0.1) + + # 读取增益 + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_GET_GAIN) + resp = self._read_response_5byte(timeout=1.0) + if resp and len(resp) == 5: + self.data["gain"] = float(resp[2]) + + await self._async_sleep(0.1) + + # 读取平滑等级 + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_GET_SMOOTH) + resp = self._read_response_5byte(timeout=1.0) + if resp and len(resp) == 5: + self.data["smooth_level"] = float(resp[2]) + + await self._async_sleep(0.1) + + # 读取平均次数 + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_GET_AVG_COUNT) + resp = self._read_response_5byte(timeout=1.0) + if resp and len(resp) == 5: + self.data["average_count"] = float(resp[2]) + + await self._async_sleep(0.1) + + # 读取积分时间单位 + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_GET_INTEG_UNIT) + resp = self._read_response_5byte(timeout=1.0) + if resp and len(resp) == 5: + self.data["integration_time_unit"] = "us" if resp[2] == 0x01 else "ms" + + self.data["status"] = "Idle" + self.data["level"] = "true" + self.logger.info("初始化完成") + return True + + @action() + async def cleanup(self) -> bool: + """清理: 停止采集, 关闭串口""" + if self._is_acquiring: + self._send_cmd(self.CMD_STOP) + self._is_acquiring = False + if self._serial and self._serial.is_open: + self._serial.close() + self.logger.info("串口已关闭") + self.data["status"] = "Offline" + self.data["level"] = "false" + return True + + # ══════════════════════════════════════════ + # 属性 (@property) — 框架只支持 float 和 str + # ══════════════════════════════════════════ + + @property + @topic_config() + def status(self) -> str: + return self.data.get("status", "Idle") + + @property + @topic_config() + def level(self) -> str: + return self.data.get("level", "false") + + @property + @topic_config() + def value(self) -> str: + return self.data.get("value", "[]") + + @property + @topic_config() + def integration_time(self) -> float: + return self.data.get("integration_time", 10000.0) + + @property + @topic_config() + def integration_time_unit(self) -> str: + return self.data.get("integration_time_unit", "ms") + + @property + @topic_config() + def gain(self) -> float: + return self.data.get("gain", 0.0) + + @property + @topic_config() + def offset(self) -> float: + return self.data.get("offset", 0.0) + + @property + @topic_config() + def smooth_level(self) -> float: + return self.data.get("smooth_level", 1.0) + + @property + @topic_config() + def average_count(self) -> float: + return self.data.get("average_count", 1.0) + + @property + @topic_config() + def trigger_mode(self) -> float: + return self.data.get("trigger_mode", 0.0) + + @property + @topic_config() + def trigger_interval(self) -> float: + return self.data.get("trigger_interval", 0.0) + + @property + @topic_config() + def version_info(self) -> str: + return self.data.get("version_info", "") + + # ══════════════════════════════════════════ + # 动作方法 — 参数类型也用 float + # ══════════════════════════════════════════ + + def _require_serial(self) -> bool: + if self._serial is None or not getattr(self._serial, "is_open", False): + self.logger.error("串口未打开,请先调用 initialize") + return False + return True + + @action() + async def start_single_acquisition(self) -> str: + """单帧采集: 启动连续采集→读取一帧→停止采集 + + Returns: + str: JSON 格式的像素数据数组 + """ + if not self._require_serial(): + return "[]" + self.data["status"] = "Acquiring" + try: + self._serial.reset_input_buffer() + # 启动连续采集 + self._send_cmd(self.CMD_CONTINUOUS_ACQ) + await self._async_sleep(0.5) + # 读取一帧 + pixels = self._read_image_frame(timeout=5.0) + # 立即停止采集 + self._send_cmd(self.CMD_STOP) + await self._async_sleep(0.1) + # 清空残留数据 + self._serial.reset_input_buffer() + + if pixels: + self._last_pixel_data = pixels + self.data["value"] = json.dumps(pixels) + self.logger.info(f"采集成功, {len(pixels)} 像素, 范围 [{min(pixels)}-{max(pixels)}]") + return self.data["value"] + else: + self.logger.error("采集失败: 未收到数据") + return "[]" + except Exception as e: + self.logger.error(f"采集异常: {e}") + return "[]" + finally: + self.data["status"] = "Idle" + + @action() + async def start_continuous_acquisition(self) -> str: + """启动连续采集模式 + + Returns: + str: 状态信息 + """ + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_CONTINUOUS_ACQ) + self._is_acquiring = True + self.data["status"] = "Acquiring" + return "continuous acquisition started" + + @action() + async def stop_acquisition(self) -> str: + """停止采集 + + Returns: + str: 状态信息 + """ + self._send_cmd(self.CMD_STOP) + self._is_acquiring = False + await self._async_sleep(0.1) + self._serial.reset_input_buffer() + self.data["status"] = "Idle" + return "acquisition stopped" + + @action() + async def read_frame(self) -> str: + """在连续采集模式下读取一帧数据 + + Returns: + str: JSON 格式的像素数据数组 + """ + pixels = self._read_image_frame(timeout=5.0) + if pixels: + self._last_pixel_data = pixels + self.data["value"] = json.dumps(pixels) + return self.data["value"] + return "[]" + + @action() + async def set_integration_time(self, time: float, unit: str = "ms") -> str: + """设置积分时间 + + Args: + time: 积分时间值 (0-65535) + unit: 时间单位, 'ms' 或 'us' + + Returns: + str: 设置结果 + """ + time_int = int(time) + # 先设置单位 + unit_val = 0x01 if unit == "us" else 0x00 + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_INTEG_UNIT, unit_val) + await self._async_sleep(0.1) + + # 设置积分时间 + data1 = (time_int >> 8) & 0xFF + data2 = time_int & 0xFF + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_INTEGRATION_TIME, data1, data2) + await self._async_sleep(0.1) + + self.data["integration_time"] = float(time_int) + self.data["integration_time_unit"] = unit + self.logger.info(f"积分时间已设置: {time_int} {unit}") + return f"integration time set to {time_int} {unit}" + + @action() + async def set_gain(self, gain: float) -> str: + """设置增益 + + Args: + gain: 增益值 (0-255) + + Returns: + str: 设置结果 + """ + gain_int = max(0, min(255, int(gain))) + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_GAIN, gain_int) + await self._async_sleep(0.1) + self.data["gain"] = float(gain_int) + return f"gain set to {gain_int}" + + @action() + async def set_offset(self, offset: float) -> str: + """设置偏移 + + Args: + offset: 偏移值 (-255 到 255) + + Returns: + str: 设置结果 + """ + offset_int = int(offset) + data1 = abs(offset_int) & 0xFF + data2 = 0x01 if offset_int >= 0 else 0x00 + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_OFFSET, data1, data2) + await self._async_sleep(0.1) + self.data["offset"] = float(offset_int) + return f"offset set to {offset_int}" + + @action() + async def set_smooth_level(self, level: float) -> str: + """设置平滑等级 + + Args: + level: 平滑等级 (1-10) + + Returns: + str: 设置结果 + """ + level_int = max(1, min(10, int(level))) + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_SET_SMOOTH, level_int) + await self._async_sleep(0.1) + self.data["smooth_level"] = float(level_int) + return f"smooth level set to {level_int}" + + @action() + async def set_average_count(self, count: float) -> str: + """设置平均次数 + + Args: + count: 平均次数 (1-255) + + Returns: + str: 设置结果 + """ + count_int = max(1, min(255, int(count))) + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_AVG_COUNT, count_int) + await self._async_sleep(0.1) + self.data["average_count"] = float(count_int) + return f"average count set to {count_int}" + + @action() + async def set_trigger_mode(self, mode: float) -> str: + """设置触发模式 + + Args: + mode: 0=软触发, 1=外部连续脉冲(Trigger In2), 2=外部单脉冲(Trigger In1) + + Returns: + str: 设置结果 + """ + mode_int = max(0, min(2, int(mode))) + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_TRIGGER_MODE, mode_int) + await self._async_sleep(0.1) + self.data["trigger_mode"] = float(mode_int) + modes = {0: "software", 1: "ext_continuous", 2: "ext_single"} + return f"trigger mode set to {modes.get(mode_int, str(mode_int))}" + + @action() + async def set_trigger_interval(self, interval: float) -> str: + """设置触发间隔 + + Args: + interval: 触发间隔值 (0-65535) + + Returns: + str: 设置结果 + """ + interval_int = int(interval) + data1 = (interval_int >> 8) & 0xFF + data2 = interval_int & 0xFF + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_TRIGGER_INTERVAL, data1, data2) + await self._async_sleep(0.1) + self.data["trigger_interval"] = float(interval_int) + return f"trigger interval set to {interval_int}" + + @action() + async def set_analog_output(self, voltage: float) -> str: + """设置模拟电压输出 + + Args: + voltage: 电压值 (0-5000 mV) + + Returns: + str: 设置结果 + """ + voltage_int = max(0, min(5000, int(voltage))) + data1 = (voltage_int >> 8) & 0xFF + data2 = voltage_int & 0xFF + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_ANALOG_OUT, data1, data2) + await self._async_sleep(0.1) + return f"analog output set to {voltage_int} mV" + + @action() + async def set_trigger_out2(self, level: float) -> str: + """设置 Trigger Out2 输出电平 + + Args: + level: 0=输出0V, 1=输出5V + + Returns: + str: 设置结果 + """ + level_int = 1 if int(level) else 0 + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_TRIGGER_OUT2, level_int) + await self._async_sleep(0.1) + return f"trigger out2 set to {'5V' if level_int else '0V'}" + + @action() + async def set_sync_output(self, enable: float) -> str: + """设置同步信号输出 + + Args: + enable: 0=禁止, 1=使能 + + Returns: + str: 设置结果 + """ + enable_int = 1 if int(enable) else 0 + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_SYNC_OUTPUT, enable_int) + await self._async_sleep(0.1) + return f"sync output {'enabled' if enable_int else 'disabled'}" + + @action() + async def save_parameters(self) -> str: + """保存当前参数到 Flash + + Returns: + str: 保存结果 + """ + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_SAVE_PARAMS, 0x01) + await self._async_sleep(0.5) + return "parameters saved to flash" + + @action() + async def read_correction_coefficients(self) -> str: + """读取矫正系数 (3 组, 用于像素→波长转换) + + Returns: + str: 矫正系数信息 + """ + coeffs = [] + for group in [0x01, 0x02, 0x03]: + self._serial.reset_input_buffer() + self._send_cmd(self.CMD_READ_CORRECTION, group) + await self._async_sleep(0.3) + + # 读取 69 字节响应: [0x81][0x29][DATA1][0x40][DATA2(64bytes)][CRC] + old_timeout = self._serial.timeout + try: + self._serial.timeout = 2.0 + # 找帧头 + header = b'' + deadline = time_module.time() + 2.0 + while time_module.time() < deadline: + b = self._serial.read(1) + if not b: + break + if b[0] == self.HEAD: + rest = self._serial.read(68) + if len(rest) == 68: + header = b + rest + break + if len(header) == 69 and header[1] == 0x29: + coeff_data = header[4:68] + coeffs.append(coeff_data) + self.logger.info(f"矫正系数组 {group} 读取成功, {len(coeff_data)} 字节") + else: + self.logger.warning(f"矫正系数组 {group} 读取失败") + coeffs.append(None) + finally: + self._serial.timeout = old_timeout + + # 解析系数: 每组 64 字节分成 4 段, 每段 16 字节作为一个字符串 + if all(c is not None for c in coeffs): + f_coeffs = ["", "", "", ""] + for c in coeffs: + for i in range(4): + segment = c[i * 16:(i + 1) * 16] + f_coeffs[i] += segment.decode('ascii', errors='ignore') + self._correction_coeffs = f_coeffs + + # 计算波长映射: wavelength = f[0]*i^3 + f[1]*i^2 + f[2]*i + f[3] + try: + f0 = float(self._correction_coeffs[0].strip('\x00').strip()) + f1 = float(self._correction_coeffs[1].strip('\x00').strip()) + f2 = float(self._correction_coeffs[2].strip('\x00').strip()) + f3 = float(self._correction_coeffs[3].strip('\x00').strip()) + self._wavelengths = [ + f0 * i * i * i + f1 * i * i + f2 * i + f3 + for i in range(self.PIXEL_COUNT) + ] + self.logger.info(f"波长映射已计算, 范围 [{self._wavelengths[0]:.2f} - {self._wavelengths[-1]:.2f}]") + return f"correction coefficients loaded, wavelength range: {self._wavelengths[0]:.2f} - {self._wavelengths[-1]:.2f}" + except (ValueError, IndexError) as e: + self.logger.warning(f"波长计算失败: {e}") + return f"correction coefficients loaded but wavelength calculation failed: {e}" + else: + return "failed to read correction coefficients" + + @action() + async def save_data_to_file(self, filename: str = "") -> str: + """保存最近一次采集数据到本地 CSV 文件 + + Args: + filename: 文件名 (为空则自动生成带时间戳的文件名) + + Returns: + str: 保存文件的完整路径 + """ + if not self._last_pixel_data: + return "no data to save, please acquire first" + + save_dir = self.config.get("save_dir", "./cmos_data") + os.makedirs(save_dir, exist_ok=True) + + if not filename: + timestamp = datetime.now().strftime("%Y%m%d_%H%M%S") + filename = f"cmos_{timestamp}.csv" + + filepath = os.path.join(save_dir, filename) + + try: + with open(filepath, 'w', newline='', encoding='utf-8') as f: + writer = csv.writer(f) + if self._wavelengths and len(self._wavelengths) == self.PIXEL_COUNT: + writer.writerow(["pixel_index", "raw_value", "wavelength"]) + for i, val in enumerate(self._last_pixel_data): + writer.writerow([i, val, f"{self._wavelengths[i]:.4f}"]) + else: + writer.writerow(["pixel_index", "raw_value"]) + for i, val in enumerate(self._last_pixel_data): + writer.writerow([i, val]) + + self.logger.info(f"数据已保存: {filepath}") + return f"saved to {os.path.abspath(filepath)}" + except Exception as e: + self.logger.error(f"保存失败: {e}") + return f"save failed: {e}" diff --git a/device_package_example/devices/cmos_detector/cmos_detector.yaml b/device_package_example/devices/cmos_detector/cmos_detector.yaml new file mode 100644 index 0000000..d2b6ed7 --- /dev/null +++ b/device_package_example/devices/cmos_detector/cmos_detector.yaml @@ -0,0 +1,546 @@ +cmos_detector: + category: + - cmos_detector + class: + action_value_mappings: + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-read_correction_coefficients: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: read_correction_coefficients参数 + type: object + type: UniLabJsonCommandAsync + auto-read_frame: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: read_frame参数 + type: object + type: UniLabJsonCommandAsync + auto-save_data_to_file: + feedback: {} + goal: {} + goal_default: + filename: '' + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + filename: + default: '' + type: string + required: [] + type: object + result: {} + required: + - goal + title: save_data_to_file参数 + type: object + type: UniLabJsonCommandAsync + auto-save_parameters: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: save_parameters参数 + type: object + type: UniLabJsonCommandAsync + auto-set_analog_output: + feedback: {} + goal: {} + goal_default: + voltage: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + voltage: + type: number + required: + - voltage + type: object + result: {} + required: + - goal + title: set_analog_output参数 + type: object + type: UniLabJsonCommandAsync + auto-set_average_count: + feedback: {} + goal: {} + goal_default: + count: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + count: + type: number + required: + - count + type: object + result: {} + required: + - goal + title: set_average_count参数 + type: object + type: UniLabJsonCommandAsync + auto-set_gain: + feedback: {} + goal: {} + goal_default: + gain: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + gain: + type: number + required: + - gain + type: object + result: {} + required: + - goal + title: set_gain参数 + type: object + type: UniLabJsonCommandAsync + auto-set_integration_time: + feedback: {} + goal: {} + goal_default: + time: null + unit: ms + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + time: + type: number + unit: + default: ms + type: string + required: + - time + type: object + result: {} + required: + - goal + title: set_integration_time参数 + type: object + type: UniLabJsonCommandAsync + auto-set_offset: + feedback: {} + goal: {} + goal_default: + offset: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + offset: + type: number + required: + - offset + type: object + result: {} + required: + - goal + title: set_offset参数 + type: object + type: UniLabJsonCommandAsync + auto-set_smooth_level: + feedback: {} + goal: {} + goal_default: + level: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + level: + type: number + required: + - level + type: object + result: {} + required: + - goal + title: set_smooth_level参数 + type: object + type: UniLabJsonCommandAsync + auto-set_sync_output: + feedback: {} + goal: {} + goal_default: + enable: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + enable: + type: number + required: + - enable + type: object + result: {} + required: + - goal + title: set_sync_output参数 + type: object + type: UniLabJsonCommandAsync + auto-set_trigger_interval: + feedback: {} + goal: {} + goal_default: + interval: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + interval: + type: number + required: + - interval + type: object + result: {} + required: + - goal + title: set_trigger_interval参数 + type: object + type: UniLabJsonCommandAsync + auto-set_trigger_mode: + feedback: {} + goal: {} + goal_default: + mode: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + mode: + type: number + required: + - mode + type: object + result: {} + required: + - goal + title: set_trigger_mode参数 + type: object + type: UniLabJsonCommandAsync + auto-set_trigger_out2: + feedback: {} + goal: {} + goal_default: + level: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + level: + type: number + required: + - level + type: object + result: {} + required: + - goal + title: set_trigger_out2参数 + type: object + type: UniLabJsonCommandAsync + auto-start_continuous_acquisition: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: start_continuous_acquisition参数 + type: object + type: UniLabJsonCommandAsync + auto-start_single_acquisition: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: start_single_acquisition参数 + type: object + type: UniLabJsonCommandAsync + auto-stop_acquisition: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: stop_acquisition参数 + type: object + type: UniLabJsonCommandAsync + module: device_package_example.devices.cmos_detector.cmos_detector:CMOSDetector + status_types: + average_count: float + gain: float + integration_time: float + integration_time_unit: str + level: str + offset: float + smooth_level: float + status: str + trigger_interval: float + trigger_mode: float + value: str + version_info: str + type: python + config_info: [] + description: '' + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + average_count: + type: number + gain: + type: number + integration_time: + type: number + integration_time_unit: + type: string + level: + type: string + offset: + type: number + smooth_level: + type: number + status: + type: string + trigger_interval: + type: number + trigger_mode: + type: number + value: + type: string + version_info: + type: string + required: + - status + - level + - value + - integration_time + - integration_time_unit + - gain + - offset + - smooth_level + - average_count + - trigger_mode + - trigger_interval + - version_info + type: object + version: 1.0.0 diff --git a/device_package_example/devices/cmos_detector/graph_example_cmos_detector.json b/device_package_example/devices/cmos_detector/graph_example_cmos_detector.json new file mode 100644 index 0000000..e191265 --- /dev/null +++ b/device_package_example/devices/cmos_detector/graph_example_cmos_detector.json @@ -0,0 +1,18 @@ +{ + "nodes": [ + { + "id": "cmos_detector_1", + "name": "LCAMV8 CMOS Detector", + "children": [], + "parent": null, + "type": "device", + "class": "cmos_detector", + "position": {"x": 400, "y": 0, "z": 0}, + "config": { + "port": "COM10", + "save_dir": "./cmos_data" + }, + "data": {} + } + ] +} diff --git a/device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.py b/device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.py new file mode 100644 index 0000000..66c84c2 --- /dev/null +++ b/device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.py @@ -0,0 +1,282 @@ +import logging +import time as time_module +from typing import Dict, Any, Optional + +try: + import serial +except ImportError: + serial = None + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="cni_laser_msl_u_532", + category=["cni_laser_msl_u_532"], + description="CNI MSL-U-532 532nm 激光器,Arduino + MCP4725 DAC 控制", + display_name="CNI 532nm 激光器", +) +class CNILaserMSLU532: + """CNI MSL-U-532-50mW laser driver via Arduino Nano + MCP4725 DAC. + + Arduino firmware accepts: SET <0-100> (percentage), returns OK:POWER= + All power control goes through DAC analog voltage on BNC port. + """ + + _ros_node: "BaseROS2DeviceNode" + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and "id" in kwargs: + device_id = kwargs.pop("id") + if config is None and "config" in kwargs: + config = kwargs.pop("config") + + self.device_id = device_id or "unknown_laser" + self.config = config or {} + self.logger = logging.getLogger(f"CNILaserMSLU532.{self.device_id}.cni_laser_msl_u_532") + + # Read parameters from config dict or kwargs (framework may expand config into kwargs) + src = self.config if self.config else kwargs + self._port: str = str(src.get("port", kwargs.get("port", "COM13"))) + self._baudrate: int = int(src.get("baudrate", kwargs.get("baudrate", 9600))) + self._timeout: float = float(src.get("timeout", kwargs.get("timeout", 2.0))) + self._max_power_mw: float = float(src.get("max_power_mw", kwargs.get("max_power_mw", 50.0))) + + self._serial: Optional[serial.Serial] = None + # Last SET percentage value (0-100), used by turn_on() to restore power + self._last_set_percent: int = 50 # default 50% + + # Pre-populate all property fields + self.data = { + "status": "Offline", + "laser_on": "false", + "power": 0.0, + "power_percentage": 0.0, + "wavelength": 532.0, + } + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + """框架回调:保存 ROS 节点引用。""" + self._ros_node = ros_node + + def _connect_serial(self) -> bool: + if self._serial is not None and self._serial.is_open: + return True + if serial is None: + self.logger.error("pyserial 未安装") + return False + self.logger.info(f"connecting to {self._port} @ {self._baudrate}") + try: + self._serial = serial.Serial( + port=self._port, + baudrate=self._baudrate, + timeout=self._timeout, + ) + self.logger.info("serial opened, waiting for Arduino reset...") + time_module.sleep(2.5) + + if self._serial.in_waiting > 0: + startup = self._serial.readline().decode("utf-8", errors="ignore").strip() + self.logger.info(f"Arduino startup: {startup}") + + self._serial.reset_input_buffer() + resp = self._send_command("IDN?") + if resp and "ArduinoUno_LaserValve" in resp: + self.logger.info(f"firmware OK: {resp}") + self._send_command("SET 0") + self.data["status"] = "Idle" + self.data["laser_on"] = "false" + self.data["power"] = 0.0 + self.data["power_percentage"] = 0.0 + return True + + self.logger.error(f"firmware check failed, got: {resp}") + self.data["status"] = "Alarm" + return False + except Exception as e: + self.logger.error(f"serial open failed: {e}") + self._serial = None + self.data["status"] = "Offline" + return False + + def _send_command(self, cmd: str) -> str: + """Send command to Arduino and read response.""" + if self._serial is None or not self._serial.is_open: + self.logger.error("serial not connected") + return "" + try: + self._serial.reset_input_buffer() + self._serial.write((cmd + "\n").encode("utf-8")) + self._serial.flush() + time_module.sleep(0.05) + resp = self._serial.readline().decode("utf-8", errors="ignore").strip() + self.logger.debug(f"TX: {cmd} -> RX: {resp}") + return resp + except Exception as e: + self.logger.error(f"serial error: {e}") + return "" + + # ── Properties ────────────────────────────────────────── + + @property + @topic_config() + def status(self) -> str: + return self.data.get("status", "Offline") + + @property + @topic_config() + def laser_on(self) -> str: + return self.data.get("laser_on", "false") + + @property + @topic_config() + def power(self) -> float: + return float(self.data.get("power", 0.0)) + + @property + @topic_config() + def power_percentage(self) -> float: + return float(self.data.get("power_percentage", 0.0)) + + @property + @topic_config() + def wavelength(self) -> float: + return float(self.data.get("wavelength", 532.0)) + + @action(description="初始化设备") + async def initialize(self) -> bool: + """打开串口并验证 Arduino 固件。""" + return self._connect_serial() + + @action(description="打开激光器") + async def turn_on(self) -> bool: + """Turn on laser, restore last power setting.""" + if self._last_set_percent <= 0: + self._last_set_percent = 50 # default to 50% if never set + resp = self._send_command(f"SET {self._last_set_percent}") + if resp.startswith("OK"): + pct = float(self._last_set_percent) + self.data["status"] = "Emitting" + self.data["laser_on"] = "true" + self.data["power_percentage"] = pct + self.data["power"] = pct / 100.0 * self._max_power_mw + self.logger.info(f"turn_on: SET {self._last_set_percent} -> {resp}") + return True + else: + self.logger.error(f"turn_on failed: {resp}") + return False + + @action(description="关闭激光器") + async def turn_off(self) -> bool: + """Turn off laser (DAC = 0V).""" + resp = self._send_command("SET 0") + if resp.startswith("OK"): + self.data["status"] = "Idle" + self.data["laser_on"] = "false" + self.data["power"] = 0.0 + self.data["power_percentage"] = 0.0 + self.logger.info(f"turn_off: SET 0 -> {resp}") + return True + else: + self.logger.error(f"turn_off failed: {resp}") + return False + + @action(description="设置激光功率(mW)") + async def set_power(self, power: float) -> bool: + """Set laser power in mW (0 ~ max_power_mw). + + Converts to percentage (0-100) for Arduino firmware. + """ + power = max(0.0, min(float(power), self._max_power_mw)) + pct = int(round(power / self._max_power_mw * 100.0)) + resp = self._send_command(f"SET {pct}") + if resp.startswith("OK"): + self._last_set_percent = pct + self.data["power_percentage"] = float(pct) + self.data["power"] = float(pct) / 100.0 * self._max_power_mw + if pct > 0: + self.data["status"] = "Emitting" + self.data["laser_on"] = "true" + else: + self.data["status"] = "Idle" + self.data["laser_on"] = "false" + self.logger.info(f"set_power({power}mW) -> SET {pct} -> {resp}") + return True + else: + self.logger.error(f"set_power failed: {resp}") + return False + + @action(description="按百分比设置激光功率") + async def set_power_percentage(self, percentage: float) -> bool: + """Set laser power by percentage (0-100%). + + Sends SET <0-100> directly to Arduino. + """ + pct = int(round(max(0.0, min(float(percentage), 100.0)))) + resp = self._send_command(f"SET {pct}") + if resp.startswith("OK"): + self._last_set_percent = pct + self.data["power_percentage"] = float(pct) + self.data["power"] = float(pct) / 100.0 * self._max_power_mw + if pct > 0: + self.data["status"] = "Emitting" + self.data["laser_on"] = "true" + else: + self.data["status"] = "Idle" + self.data["laser_on"] = "false" + self.logger.info(f"set_power_percentage({percentage}%) -> SET {pct} -> {resp}") + return True + else: + self.logger.error(f"set_power_percentage failed: {resp}") + return False + + @action(description="紧急停止") + async def emergency_stop(self) -> bool: + """Emergency stop - immediately set DAC to 0.""" + resp = self._send_command("SET 0") + self._last_set_percent = 0 + self.data["status"] = "Idle" + self.data["laser_on"] = "false" + self.data["power"] = 0.0 + self.data["power_percentage"] = 0.0 + self.logger.info(f"emergency_stop: SET 0 -> {resp}") + return True + + @action(description="清理资源") + async def cleanup(self) -> bool: + """Cleanup - turn off laser and close serial.""" + try: + if self._serial and self._serial.is_open: + self._send_command("SET 0") + self._serial.close() + self.logger.info("cleanup: serial closed") + except Exception as e: + self.logger.error(f"cleanup error: {e}") + self._serial = None + self.data["status"] = "Offline" + self.data["laser_on"] = "false" + self.data["power"] = 0.0 + self.data["power_percentage"] = 0.0 + return True diff --git a/device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.yaml b/device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.yaml new file mode 100644 index 0000000..ad2de58 --- /dev/null +++ b/device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.yaml @@ -0,0 +1,226 @@ +cni_laser_msl_u_532: + category: + - cni_laser_msl_u_532 + class: + action_value_mappings: + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-emergency_stop: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: emergency_stop参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-set_power: + feedback: {} + goal: {} + goal_default: + power: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + power: + type: number + required: + - power + type: object + result: {} + required: + - goal + title: set_power参数 + type: object + type: UniLabJsonCommandAsync + auto-set_power_percentage: + feedback: {} + goal: {} + goal_default: + percentage: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + percentage: + type: number + required: + - percentage + type: object + result: {} + required: + - goal + title: set_power_percentage参数 + type: object + type: UniLabJsonCommandAsync + auto-turn_off: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: turn_off参数 + type: object + type: UniLabJsonCommandAsync + auto-turn_on: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: turn_on参数 + type: object + type: UniLabJsonCommandAsync + module: device_package_example.devices.cni_laser_msl_u_532.cni_laser_msl_u_532:CNILaserMSLU532 + status_types: + laser_on: str + power: float + power_percentage: float + status: str + wavelength: float + type: python + config_info: [] + description: '' + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + laser_on: + type: string + power: + type: number + power_percentage: + type: number + status: + type: string + wavelength: + type: number + required: + - status + - laser_on + - power + - power_percentage + - wavelength + type: object + version: 1.0.0 diff --git a/device_package_example/devices/cni_laser_msl_u_532/graph_example_cni_laser_msl_u_532.json b/device_package_example/devices/cni_laser_msl_u_532/graph_example_cni_laser_msl_u_532.json new file mode 100644 index 0000000..609ff57 --- /dev/null +++ b/device_package_example/devices/cni_laser_msl_u_532/graph_example_cni_laser_msl_u_532.json @@ -0,0 +1,24 @@ +{ + "nodes": [ + { + "id": "cni_laser_1", + "name": "CNI MSL-U-532 激光器", + "children": [], + "parent": null, + "type": "device", + "class": "cni_laser_msl_u_532", + "position": { + "x": 0, + "y": 0, + "z": 0 + }, + "config": { + "port": "COM13", + "baudrate": 9600, + "timeout": 2, + "max_power_mw": 50.0 + }, + "data": {} + } + ] +} diff --git a/device_package_example/devices/daheng_gci060505/daheng_gci060505.py b/device_package_example/devices/daheng_gci060505/daheng_gci060505.py new file mode 100644 index 0000000..dbdf7e3 --- /dev/null +++ b/device_package_example/devices/daheng_gci060505/daheng_gci060505.py @@ -0,0 +1,219 @@ +import logging +import time as time_module +from typing import Dict, Any + +try: + import serial +except ImportError: + serial = None + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="daheng_gci060505", + category=["custom", "daheng_gci060505"], + description="大恒 GCI-060505 LED 光源,Arduino + MCP4725 DAC 控制", + display_name="GCI-060505 LED 光源", +) +class DahengGCI060505: + """大恒光电 GCI-060505 LED光源驱动(通过 Arduino + MCP4725 DAC 控制)""" + + _ros_node: "BaseROS2DeviceNode" + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and 'id' in kwargs: + device_id = kwargs.pop('id') + if config is None and 'config' in kwargs: + config = kwargs.pop('config') + self.device_id = device_id or "unknown_device" + self.config = config or {} + self.logger = logging.getLogger(f"DahengGCI060505.{self.device_id}.daheng_gci060505") + + self._port = self.config.get("port", "COM14") + self._baudrate = self.config.get("baudrate", 115200) + self._timeout = self.config.get("timeout", 2) + self._ser = None + + self.data = { + "status": "Idle", + "brightness": 0.0, + "light_on": False, + "max_brightness": 100.0, + } + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + def _open_serial(self) -> bool: + if self._ser is not None and self._ser.is_open: + return True + if serial is None: + self.logger.error("pyserial 未安装,请运行: pip install pyserial") + return False + try: + self._ser = serial.Serial( + port=self._port, + baudrate=self._baudrate, + timeout=self._timeout, + ) + time_module.sleep(2) + self._ser.reset_input_buffer() + self.logger.info(f"串口 {self._port} 已打开") + return True + except Exception as e: + self.logger.error(f"串口打开失败: {e}") + self._ser = None + return False + + def _send_command(self, cmd: str) -> str: + if self._ser is None or not self._ser.is_open: + if not self._open_serial(): + return "" + try: + self._ser.reset_input_buffer() + self._ser.write(f"{cmd}\n".encode("ascii")) + self._ser.flush() + response = self._ser.readline().decode("ascii", errors="ignore").strip() + self.logger.debug(f"TX: {cmd} → RX: {response}") + return response + except Exception as e: + self.logger.error(f"通信失败: {e}") + return "" + + def _close_serial(self): + if self._ser is not None and self._ser.is_open: + try: + self._ser.close() + except Exception: + pass + self._ser = None + + def _refresh_from_arduino(self): + response = self._send_command("STATUS") + if "OK:STATUS:" in response: + try: + parts = response.split(":") + idx = parts.index("STATUS") + on_off = parts[idx + 1] + bright = int(parts[idx + 2]) + self.data["light_on"] = (on_off == "ON") + self.data["brightness"] = float(bright) + self.data["status"] = "On" if self.data["light_on"] else "Idle" + except (ValueError, IndexError) as e: + self.logger.warning(f"STATUS 解析失败: {response}, 错误: {e}") + + @action(description="初始化设备") + async def initialize(self) -> bool: + """打开串口并验证 Arduino 通信。""" + if not self._open_serial(): + self.data["status"] = "Error" + return False + response = self._send_command("PING") + if "PONG" in response: + self.logger.info("Arduino 通信正常") + self.data["status"] = "Idle" + self._refresh_from_arduino() + return True + self.logger.error(f"PING 测试失败,响应: {response}") + self.data["status"] = "Error" + return False + + @action(description="清理资源") + async def cleanup(self) -> bool: + """关灯并关闭串口。""" + try: + self._send_command("OFF") + except Exception: + pass + self._close_serial() + self.data["status"] = "Offline" + self.data["light_on"] = False + return True + + @property + @topic_config() + def status(self) -> str: + return self.data.get("status", "Idle") + + @property + @topic_config() + def brightness(self) -> float: + return self.data.get("brightness", 0.0) + + @property + @topic_config() + def light_on(self) -> bool: + return self.data.get("light_on", False) + + @property + @topic_config() + def max_brightness(self) -> float: + return self.data.get("max_brightness", 100.0) + + @action(description="开灯") + async def turn_on(self) -> bool: + self.data["status"] = "Busy" + response = self._send_command("ON") + ok = "OK" in response + if ok: + self.data["light_on"] = True + if self.data["brightness"] == 0.0: + self.data["brightness"] = 100.0 + self.data["status"] = "On" + else: + self.data["status"] = "Error" + return ok + + @action(description="关灯") + async def turn_off(self) -> bool: + self.data["status"] = "Busy" + response = self._send_command("OFF") + ok = "OK" in response + if ok: + self.data["light_on"] = False + self.data["status"] = "Idle" + else: + self.data["status"] = "Error" + return ok + + @action(description="设置亮度") + async def set_brightness(self, brightness: float) -> bool: + brightness = max(0.0, min(100.0, float(brightness))) + self.data["status"] = "Busy" + response = self._send_command(f"BRIGHT:{int(brightness)}") + ok = "OK" in response + if ok: + self.data["brightness"] = brightness + self.data["light_on"] = brightness > 0 + self.data["status"] = "On" if brightness > 0 else "Idle" + else: + self.data["status"] = "Error" + return ok + + @action(description="刷新设备状态", always_free=True) + async def refresh_status(self) -> bool: + self._refresh_from_arduino() + return True diff --git a/device_package_example/devices/daheng_gci060505/daheng_gci060505.yaml b/device_package_example/devices/daheng_gci060505/daheng_gci060505.yaml new file mode 100644 index 0000000..a7d72f6 --- /dev/null +++ b/device_package_example/devices/daheng_gci060505/daheng_gci060505.yaml @@ -0,0 +1,198 @@ +daheng_gci060505: + category: + - custom + - daheng_gci060505 + class: + action_value_mappings: + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-refresh_status: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: refresh_status参数 + type: object + type: UniLabJsonCommandAsync + auto-set_brightness: + feedback: {} + goal: {} + goal_default: + brightness: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + brightness: + type: number + required: + - brightness + type: object + result: {} + required: + - goal + title: set_brightness参数 + type: object + type: UniLabJsonCommandAsync + auto-turn_off: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: turn_off参数 + type: object + type: UniLabJsonCommandAsync + auto-turn_on: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: turn_on参数 + type: object + type: UniLabJsonCommandAsync + module: device_package_example.devices.daheng_gci060505.daheng_gci060505:DahengGCI060505 + status_types: + brightness: float + light_on: bool + max_brightness: float + status: str + type: python + config_info: [] + description: 大恒光电 GCI-060505 LED 光源 (控制器 GCI-060551), 通过 Arduino + MCP4725 DAC 中间层控制 + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + brightness: + type: number + light_on: + type: boolean + max_brightness: + type: number + status: + type: string + required: + - status + - brightness + - light_on + - max_brightness + type: object + version: 1.0.0 diff --git a/device_package_example/devices/daheng_gci060505/graph_example_daheng_gci060505.json b/device_package_example/devices/daheng_gci060505/graph_example_daheng_gci060505.json new file mode 100644 index 0000000..aa904f4 --- /dev/null +++ b/device_package_example/devices/daheng_gci060505/graph_example_daheng_gci060505.json @@ -0,0 +1,19 @@ +{ + "nodes": [ + { + "id": "daheng_light_1", + "name": "大恒光电 GCI-060505 LED 光源", + "children": [], + "parent": null, + "type": "device", + "class": "daheng_gci060505", + "position": {"x": 100, "y": -300, "z": 0}, + "config": { + "port": "COM14", + "baudrate": 9600, + "timeout": 2 + }, + "data": {} + } + ] +} diff --git a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py new file mode 100644 index 0000000..3484b65 --- /dev/null +++ b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py @@ -0,0 +1,511 @@ +import logging +import time as time_module +from typing import Dict, Any, Optional + +try: + import numpy as np +except ImportError: + np = None + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + +try: + from harvesters.core import Harvester +except ImportError: + Harvester = None + + +@device( + id="daheng_hd_r630c", + category=["sensor", "daheng_hd_r630c"], + description="度申 HD-R630C USB3 工业相机", + display_name="HD-R630C 工业相机", +) +class DahengHdR630c: + """度申 DO3THINK M3S630-H-O2C (HD-R630C-U3) USB3 Vision 彩色工业相机驱动。 + + 通过 Harvesters (GenICam/GenTL) 通用接口与相机通信,支持单帧采集、 + 连续采集、曝光时间和增益设置等功能。 + + 依赖: + - harvesters: pip install harvesters + - GenTL Producer: 度申 DVPCameraTL64.cti + """ + + _ros_node: "BaseROS2DeviceNode" + + # 默认 .cti 文件路径(度申 64 位) + DEFAULT_CTI_PATH = r"C:\Program Files (x86)\Do3think\DVP2 x64\DVPCameraTL64.cti" + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and "id" in kwargs: + device_id = kwargs.pop("id") + if config is None and "config" in kwargs: + config = kwargs.pop("config") + self.device_id = device_id or "unknown_device" + self.config = config or {} + self.logger = logging.getLogger(f"DahengHdR630c.{self.device_id}") + + # ── 预填充所有属性字段的默认值(硬约束 #3)── + self.data: Dict[str, Any] = { + "status": "Idle", + "exposure_time": 10000.0, # 默认曝光时间 10ms (10000μs) + "gain": 0.0, # 默认增益 0dB + "frame_rate": 0.0, # 当前帧率 + "image_width": 0, # 图像宽度 px + "image_height": 0, # 图像高度 px + "is_streaming": False, # 是否连续采集中 + "last_frame_id": 0, # 最后一帧帧号 + # 兼容 sensor 基础接口 + "level": False, # 设备是否就绪(True=已连接) + "last_image_path": "", # 最后保存的图片路径 + "rssi": 0, # 信号强度(USB相机固定为100) + } + + # 内部状态 + self._harvester: Optional[Harvester] = None + self._ia = None # ImageAcquirer + self._last_image: Optional[np.ndarray] = None + + # 从 config 读取配置 + self._cti_path: str = self.config.get("cti_path", self.DEFAULT_CTI_PATH) + self._device_index: int = self.config.get("device_index", 0) + self._default_exposure: float = self.config.get("default_exposure_time", 10000.0) + self._default_gain: float = self.config.get("default_gain", 0.0) + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + """框架回调:注入 ROS 节点引用。""" + self._ros_node = ros_node + + # ════════════════════════════════════════════ + # 生命周期方法 + # ════════════════════════════════════════════ + + @action() + async def initialize(self) -> bool: + """初始化相机连接。 + + 通过 Harvesters + GenTL 枚举设备并打开相机,配置默认参数。 + + Returns: + bool: 初始化是否成功 + """ + if Harvester is None: + self.logger.error("harvesters 未安装。请执行: pip install harvesters") + self.data["status"] = "Offline" + return False + + try: + self.data["status"] = "Busy" + + # 创建 Harvester 并加载 GenTL Producer + self._harvester = Harvester() + cti_path = self._cti_path + self.logger.info(f"加载 GenTL Producer: {cti_path}") + + # 如果 config 传入的路径无效,使用默认路径兜底 + import os + if not os.path.isfile(cti_path): + cti_path = self.DEFAULT_CTI_PATH + self.logger.warning(f"config 中 cti_path 无效,使用默认路径: {cti_path}") + + self._harvester.add_file(cti_path) + self.logger.info("GenTL Producer 已加载,开始枚举设备...") + self._harvester.update() + + dev_count = len(self._harvester.device_info_list) + self.logger.info(f"枚举完成,发现 {dev_count} 台设备。") + + if dev_count == 0: + # 尝试多次枚举(某些相机需要等待) + import asyncio + for retry in range(3): + self.logger.info(f"重试枚举第 {retry + 1} 次...") + await self._ros_node.sleep(1.0) + self._harvester.update() + dev_count = len(self._harvester.device_info_list) + self.logger.info(f"重试结果:发现 {dev_count} 台设备。") + if dev_count > 0: + break + + if dev_count == 0: + self.logger.error("多次枚举后仍未发现相机设备。") + self.data["status"] = "Offline" + return False + + self.logger.info(f"发现 {dev_count} 台相机设备。") + for i, dev in enumerate(self._harvester.device_info_list): + self.logger.info(f" 设备 {i}: {dev.display_name} (model={dev.model})") + + # 打开指定索引的相机 + self._ia = self._harvester.create(self._device_index) + + # 读取相机节点参数 + node_map = self._ia.remote_device.node_map + + # 读取图像尺寸 + try: + self.data["image_width"] = node_map.Width.value + self.data["image_height"] = node_map.Height.value + except Exception: + self.logger.warning("无法读取图像尺寸。") + + # 设置默认曝光时间 + try: + node_map.ExposureTime.value = self._default_exposure + self.data["exposure_time"] = node_map.ExposureTime.value + except Exception: + self.logger.warning("无法设置曝光时间,尝试 ExposureTimeAbs...") + try: + node_map.ExposureTimeAbs.value = self._default_exposure + self.data["exposure_time"] = node_map.ExposureTimeAbs.value + except Exception: + self.logger.warning("无法设置曝光时间。") + + # 设置默认增益 + try: + node_map.Gain.value = self._default_gain + self.data["gain"] = node_map.Gain.value + except Exception: + try: + node_map.GainRaw.value = int(self._default_gain) + self.data["gain"] = float(node_map.GainRaw.value) + except Exception: + self.logger.warning("无法设置增益。") + + # 读取帧率 + try: + self.data["frame_rate"] = node_map.AcquisitionFrameRate.value + except Exception: + self.logger.warning("无法读取帧率。") + + # 更新传感器兼容属性 + self.data["level"] = True + self.data["rssi"] = 100 # USB 直连,信号满格 + + self.data["status"] = "Idle" + self.logger.info( + f"相机初始化成功: {self.data['image_width']}x{self.data['image_height']}, " + f"曝光={self.data['exposure_time']}μs, 增益={self.data['gain']}dB" + ) + return True + + except Exception as e: + self.logger.error(f"相机初始化失败: {e}") + self.data["status"] = "Offline" + self.data["level"] = False + return False + + @action() + async def cleanup(self) -> bool: + """关闭相机并释放资源。 + + Returns: + bool: 清理是否成功 + """ + try: + if self._ia is not None: + # 如果正在采集,先停止 + if self.data["is_streaming"]: + self._ia.stop() + self.data["is_streaming"] = False + + self._ia.destroy() + self._ia = None + self.logger.info("ImageAcquirer 已销毁。") + + if self._harvester is not None: + self._harvester.reset() + self._harvester = None + self.logger.info("Harvester 已释放。") + + self.data["status"] = "Offline" + self.data["level"] = False + self.data["rssi"] = 0 + return True + + except Exception as e: + self.logger.error(f"相机清理失败: {e}") + self.data["status"] = "Offline" + return False + + # ════════════════════════════════════════════ + # 动作方法 + # ════════════════════════════════════════════ + + @action() + @action() + async def snap(self) -> str: + """单帧采集并保存图片,返回文件路径。""" + if self._ia is None: + self.logger.error("相机未初始化,无法采集。") + return "" + + try: + self.data["status"] = "Busy" + was_streaming = self.data["is_streaming"] + + if np is None: + self.logger.error("numpy 未安装") + self.data["status"] = "Idle" + return "" + + # 如果没有在连续采集,先启动采集 + if not was_streaming: + self._ia.start() + + # 获取一帧图像(超时 5 秒) + with self._ia.fetch(timeout=5.0) as buffer: + component = buffer.payload.components[0] + + # 获取图像数据 + width = component.width + height = component.height + + # 从 buffer 拿到 numpy 数据 + image_data = component.data.reshape(height, width, -1) if component.data.ndim == 1 else component.data + + if image_data.ndim == 2: + # 灰度图像,转成 3 通道 + self._last_image = np.stack([image_data] * 3, axis=-1).copy() + elif image_data.shape[2] == 3: + # RGB -> BGR (OpenCV 格式) + self._last_image = image_data[:, :, ::-1].copy() + elif image_data.shape[2] == 4: + # RGBA -> BGR + self._last_image = image_data[:, :, 2::-1].copy() + else: + self._last_image = image_data.copy() + + self.data["last_frame_id"] = self.data["last_frame_id"] + 1 + self.data["image_width"] = width + self.data["image_height"] = height + + if not was_streaming: + self._ia.stop() + + # 保存图片到文件 + save_dir = self.config.get("save_dir", "./captured_images") + import os + os.makedirs(save_dir, exist_ok=True) + + timestamp = time_module.strftime("%Y%m%d_%H%M%S") + filename = f"snap_{self.data['last_frame_id']}_{timestamp}.png" + filepath = os.path.join(save_dir, filename) + + try: + import cv2 + cv2.imwrite(filepath, self._last_image) + self.data["last_image_path"] = os.path.abspath(filepath) + self.logger.info(f"图片已保存: {os.path.abspath(filepath)}") + except ImportError: + # 没有 cv2,用 PIL 保存 + try: + from PIL import Image + # self._last_image 是 BGR 格式,转 RGB + rgb_image = self._last_image[:, :, ::-1] + Image.fromarray(rgb_image).save(filepath) + self.data["last_image_path"] = os.path.abspath(filepath) + self.logger.info(f"图片已保存: {os.path.abspath(filepath)}") + except ImportError: + self.logger.warning("未安装 cv2 或 PIL,无法保存图片到文件。") + + self.data["status"] = "Streaming" if was_streaming else "Idle" + self.logger.info( + f"采集成功: frame_id={self.data['last_frame_id']}, " + f"shape={self._last_image.shape if self._last_image is not None else 'N/A'}" + ) + return self.data.get("last_image_path", "") + + except Exception as e: + self.logger.error(f"单帧采集失败: {e}") + if not was_streaming: + try: + self._ia.stop() + except Exception: + pass + self.data["status"] = "Idle" + return "" + + @action() + async def start_stream(self): + """开始连续采集。 + + 启动相机的连续数据流,后续可通过 snap() 获取最新帧。 + """ + if self._ia is None: + self.logger.error("相机未初始化,无法开始连续采集。") + return + + if self.data["is_streaming"]: + self.logger.warning("相机已在连续采集中。") + return + + try: + self.data["status"] = "Busy" + self._ia.start() + self.data["is_streaming"] = True + self.data["status"] = "Streaming" + self.logger.info("连续采集已启动。") + except Exception as e: + self.logger.error(f"启动连续采集失败: {e}") + self.data["status"] = "Idle" + + @action() + async def stop_stream(self): + """停止连续采集。""" + if self._ia is None: + self.logger.error("相机未初始化。") + return + + if not self.data["is_streaming"]: + self.logger.warning("相机未在连续采集中。") + return + + try: + self._ia.stop() + self.data["is_streaming"] = False + self.data["status"] = "Idle" + self.logger.info("连续采集已停止。") + except Exception as e: + self.logger.error(f"停止连续采集失败: {e}") + + @action() + async def set_exposure_time(self, exposure_time: float): + """设置曝光时间。 + + Args: + exposure_time: 曝光时间,单位 μs(微秒) + """ + if self._ia is None: + self.logger.error("相机未初始化,无法设置曝光时间。") + return + + try: + node_map = self._ia.remote_device.node_map + try: + node_map.ExposureTime.value = exposure_time + self.data["exposure_time"] = node_map.ExposureTime.value + except Exception: + node_map.ExposureTimeAbs.value = exposure_time + self.data["exposure_time"] = node_map.ExposureTimeAbs.value + self.logger.info(f"曝光时间已设置为 {self.data['exposure_time']} μs") + except Exception as e: + self.logger.error(f"设置曝光时间失败: {e}") + + @action() + async def set_gain(self, gain: float): + """设置增益。 + + Args: + gain: 增益值,单位 dB + """ + if self._ia is None: + self.logger.error("相机未初始化,无法设置增益。") + return + + try: + node_map = self._ia.remote_device.node_map + try: + node_map.Gain.value = gain + self.data["gain"] = node_map.Gain.value + except Exception: + node_map.GainRaw.value = int(gain) + self.data["gain"] = float(node_map.GainRaw.value) + self.logger.info(f"增益已设置为 {self.data['gain']} dB") + except Exception as e: + self.logger.error(f"设置增益失败: {e}") + + # ════════════════════════════════════════════ + # 属性 (Properties) + # ════════════════════════════════════════════ + + @property + @topic_config() + def status(self) -> str: + """设备状态: "Idle" / "Busy" / "Streaming" / "Offline" """ + return self.data.get("status", "Idle") + + @property + @topic_config() + def exposure_time(self) -> float: + """当前曝光时间(μs)。""" + return self.data.get("exposure_time", 10000.0) + + @property + @topic_config() + def gain(self) -> float: + """当前增益(dB)。""" + return self.data.get("gain", 0.0) + + @property + @topic_config() + def frame_rate(self) -> float: + """当前帧率(fps)。""" + return self.data.get("frame_rate", 0.0) + + @property + @topic_config() + def image_width(self) -> float: + """图像宽度(px)。""" + return float(self.data.get("image_width", 0)) + + @property + @topic_config() + def image_height(self) -> float: + """图像高度(px)。""" + return float(self.data.get("image_height", 0)) + + @property + @topic_config() + def is_streaming(self) -> bool: + """是否在连续采集中。""" + return self.data.get("is_streaming", False) + + @property + @topic_config() + def last_frame_id(self) -> float: + """最后一帧的帧号。""" + return float(self.data.get("last_frame_id", 0)) + + @property + @topic_config() + def level(self) -> bool: + """设备是否在线(兼容 sensor 基础接口)。""" + return self.data.get("level", False) + + @property + @topic_config() + def rssi(self) -> float: + """信号强度(兼容 sensor 基础接口,USB 直连固定为 100)。""" + return float(self.data.get("rssi", 0)) + + def get_last_image(self) -> Optional[np.ndarray]: + """获取最近一次采集的图像数据。 + + Returns: + numpy.ndarray or None: BGR 格式图像数据 + """ + return self._last_image diff --git a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml new file mode 100644 index 0000000..a8c1352 --- /dev/null +++ b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml @@ -0,0 +1,360 @@ +daheng_hd_r630c: + action_value_mappings: + set_exposure_time: + goal: + exposure_time: exposure_time + goal_default: + exposure_time: 10000.0 + handles: {} + placeholder_keys: {} + result: + success: success + schema: + properties: + goal: + properties: + exposure_time: + type: number + required: + - exposure_time + type: object + required: + - goal + title: set_exposure_time参数 + type: object + type: UniLabJsonCommandAsync + set_gain: + goal: + gain: gain + goal_default: + gain: 0.0 + handles: {} + placeholder_keys: {} + result: + success: success + schema: + properties: + goal: + properties: + gain: + type: number + required: + - gain + type: object + required: + - goal + title: set_gain参数 + type: object + type: UniLabJsonCommandAsync + snap: + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: + success: success + schema: + properties: + goal: + properties: {} + type: object + required: + - goal + title: snap参数 + type: object + type: UniLabJsonCommandAsync + start_stream: + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: + success: success + schema: + properties: + goal: + properties: {} + type: object + required: + - goal + title: start_stream参数 + type: object + type: UniLabJsonCommandAsync + stop_stream: + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: + success: success + schema: + properties: + goal: + properties: {} + type: object + required: + - goal + title: stop_stream参数 + type: object + type: UniLabJsonCommandAsync + category: + - sensor + - daheng_hd_r630c + class: + action_value_mappings: + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-set_exposure_time: + feedback: {} + goal: {} + goal_default: + exposure_time: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + exposure_time: + type: number + required: + - exposure_time + type: object + result: {} + required: + - goal + title: set_exposure_time参数 + type: object + type: UniLabJsonCommandAsync + auto-set_gain: + feedback: {} + goal: {} + goal_default: + gain: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + gain: + type: number + required: + - gain + type: object + result: {} + required: + - goal + title: set_gain参数 + type: object + type: UniLabJsonCommandAsync + auto-snap: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: snap参数 + type: object + type: UniLabJsonCommandAsync + auto-start_stream: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: start_stream参数 + type: object + type: UniLabJsonCommandAsync + auto-stop_stream: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: stop_stream参数 + type: object + type: UniLabJsonCommandAsync + module: device_package_example.devices.daheng_hd_r630c.daheng_hd_r630c:DahengHdR630c + status_types: + exposure_time: float + frame_rate: float + gain: float + image_height: int + image_width: int + is_streaming: bool + last_frame_id: int + last_image: String + level: bool + rssi: int + status: str + type: python + config_info: [] + description: 度申 DO3THINK M3S630-H-O2C (HD-R630C-U3) USB3 Vision 彩色工业相机 + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + exposure_time: + type: number + frame_rate: + type: number + gain: + type: number + image_height: + type: integer + image_width: + type: integer + is_streaming: + type: boolean + last_frame_id: + type: integer + last_image: + type: string + level: + type: boolean + rssi: + type: integer + status: + type: string + required: + - status + - exposure_time + - gain + - frame_rate + - image_width + - image_height + - is_streaming + - last_frame_id + - level + - rssi + - last_image + type: object + status_types: + exposure_time: Float64 + frame_rate: Float64 + gain: Float64 + image_height: Int64 + image_width: Int64 + is_streaming: Bool + last_frame_id: Int64 + level: Bool + rssi: Int64 + status: String + version: 1.0.0 diff --git a/device_package_example/devices/daheng_hd_r630c/graph_example_daheng_hd_r630c.json b/device_package_example/devices/daheng_hd_r630c/graph_example_daheng_hd_r630c.json new file mode 100644 index 0000000..d16a55a --- /dev/null +++ b/device_package_example/devices/daheng_hd_r630c/graph_example_daheng_hd_r630c.json @@ -0,0 +1,35 @@ +{ + "nodes": [ + { + "id": "daheng_camera_1", + "name": "度申 M3S630-H-O2C 工业相机", + "children": [], + "parent": null, + "type": "device", + "class": "daheng_hd_r630c", + "position": { + "x": 0, + "y": 0, + "z": 0 + }, + "config": { + "cti_path": "C:\\Program Files (x86)\\Do3think\\DVP2 x64\\DVPCameraTL64.cti", + "device_index": 0, + "default_exposure_time": 10000.0, + "default_gain": 0.0 + }, + "data": { + "status": "Idle", + "exposure_time": 10000.0, + "gain": 0.0, + "frame_rate": 0.0, + "image_width": 0, + "image_height": 0, + "is_streaming": false, + "last_frame_id": 0, + "level": false, + "rssi": 0 + } + } + ] +} \ No newline at end of file diff --git a/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.yaml b/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.yaml index 4790e70..dc4b28f 100644 --- a/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.yaml +++ b/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.yaml @@ -3,7 +3,7 @@ dhjf_circulation_bath: - dhjf_circulation_bath class: action_value_mappings: {} - module: unilabos.devices.temperature.dhjf_circulation_bath:DHJFCirculationBath + module: device_package_example.devices.dhjf_circulation_bath.dhjf_circulation_bath:DHJFCirculationBath status_types: {} type: python config_info: [] diff --git a/device_package_example/devices/duco_gcr5/duco_gcr5.yaml b/device_package_example/devices/duco_gcr5/duco_gcr5.yaml index da63683..5b7fadc 100644 --- a/device_package_example/devices/duco_gcr5/duco_gcr5.yaml +++ b/device_package_example/devices/duco_gcr5/duco_gcr5.yaml @@ -315,7 +315,7 @@ duco_gcr5: title: stop参数 type: object type: UniLabJsonCommandAsync - module: unilabos.devices.robot_arm.duco_gcr5:DucoGCR5 + module: device_package_example.devices.duco_gcr5.duco_gcr5:DucoGCR5 status_types: error_message: str joint_torque: String diff --git a/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py b/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py new file mode 100644 index 0000000..593bc08 --- /dev/null +++ b/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py @@ -0,0 +1,635 @@ +""" +Electrolytic Cell Gripper Workstation Driver (电解池夹爪工作站) +Combines 2x QYL stepper motors + 1x DH PGE gripper into a single device +with two high-level actions: pick_sample and place_sample. + +All three physical devices share COM29 via RS-485 Modbus RTU. +Motor 1 (slave_id=1), Motor 2 (slave_id=2), Gripper (slave_id=5). + +Communication: 115200, 8N1 +Motor: FC 03/06/10, speed/accel = register raw value (5000 in debug software = reg 5000) +Gripper: FC 03/06 + +v7: Self-contained driver with lazy serial initialization. + Serial port is opened on first use (not only in initialize()), + so it works regardless of whether the framework calls initialize(). +""" + +import logging +import struct +import time as time_module +from typing import Dict, Any, Optional + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + +try: + import serial + from serial import Serial +except ImportError: + serial = None + Serial = None + + +# ═══════════════════════════════════════════════════════════════════ +# CRC16 Modbus +# ═══════════════════════════════════════════════════════════════════ + +def _crc16_modbus(data: bytes) -> bytes: + """Calculate Modbus RTU CRC16, returns 2 bytes (low, high).""" + crc = 0xFFFF + for byte in data: + crc ^= byte + for _ in range(8): + if crc & 0x0001: + crc = (crc >> 1) ^ 0xA001 + else: + crc >>= 1 + return struct.pack(" bytes: + frame = struct.pack(">B B H H", slave_id, 0x03, register, count) + return frame + _crc16_modbus(frame) + + @staticmethod + def _build_write_single_frame(slave_id: int, register: int, value: int) -> bytes: + frame = struct.pack(">B B H H", slave_id, 0x06, register, value & 0xFFFF) + return frame + _crc16_modbus(frame) + + @staticmethod + def _build_write_multiple_frame(slave_id: int, start_register: int, values: list) -> bytes: + count = len(values) + byte_count = count * 2 + frame = struct.pack(">B B H H B", slave_id, 0x10, start_register, count, byte_count) + for v in values: + frame += struct.pack(">H", v & 0xFFFF) + return frame + _crc16_modbus(frame) + + # ── Send / Receive ────────────────────────────────────────── + + def send_and_receive(self, frame: bytes, expect_len: int) -> Optional[bytes]: + if self._ser is None or not self._ser.is_open: + self.logger.error("Serial not open") + return None + + self.logger.debug(f"TX: {frame.hex(' ')}") + self._ser.reset_input_buffer() + self._ser.write(frame) + time_module.sleep(0.05) + + raw = self._ser.read(expect_len + 10) + self.logger.debug(f"RX: {raw.hex(' ') if raw else '(empty)'}") + + if len(raw) < expect_len: + self.logger.warning(f"Short response: expected >={expect_len}, got {len(raw)}") + if len(raw) == 0: + return None + + fc_sent = frame[1] + slave_id = frame[0] + for i in range(len(raw) - 1): + if raw[i] == slave_id and raw[i + 1] == fc_sent: + resp = raw[i:] + if len(resp) >= expect_len: + payload = resp[:expect_len - 2] + crc_recv = resp[expect_len - 2:expect_len] + if _crc16_modbus(payload) == crc_recv: + return resp[:expect_len] + else: + self.logger.warning("CRC mismatch") + return resp[:expect_len] + break + if raw[i] == slave_id and raw[i + 1] == (fc_sent | 0x80): + error_code = raw[i + 2] if i + 2 < len(raw) else 0xFF + self.logger.error(f"Modbus error: FC=0x{raw[i+1]:02X}, err=0x{error_code:02X}") + return None + + self.logger.warning("Could not locate valid response frame") + return raw[:expect_len] if len(raw) >= expect_len else None + + # ── High-level register operations ────────────────────────── + + def read_registers(self, slave_id: int, start: int, count: int = 1) -> Optional[list]: + frame = self._build_read_frame(slave_id, start, count) + expect = 3 + count * 2 + 2 + resp = self.send_and_receive(frame, expect) + if resp is None or len(resp) < expect: + return None + values = [] + for i in range(count): + offset = 3 + i * 2 + values.append(struct.unpack(">H", resp[offset:offset + 2])[0]) + return values + + def write_single(self, slave_id: int, register: int, value: int) -> bool: + frame = self._build_write_single_frame(slave_id, register, value) + resp = self.send_and_receive(frame, 8) + return resp is not None + + def write_multiple(self, slave_id: int, start: int, values: list) -> bool: + frame = self._build_write_multiple_frame(slave_id, start, values) + resp = self.send_and_receive(frame, 8) + return resp is not None + + +# ═══════════════════════════════════════════════════════════════════ +# Helper: signed 32-bit conversion +# ═══════════════════════════════════════════════════════════════════ + +def _from_signed32(val: int) -> tuple: + if val < 0: + val += 0x100000000 + return ((val >> 16) & 0xFFFF, val & 0xFFFF) + +def _to_signed32(high: int, low: int) -> int: + val = (high << 16) | low + if val >= 0x80000000: + val -= 0x100000000 + return val + + +# ═══════════════════════════════════════════════════════════════════ +# Motor register addresses +# ═══════════════════════════════════════════════════════════════════ + +_M_STATUS = 0x0000 +_M_POS_H = 0x0001 +_M_POS_L = 0x0002 +_M_SPEED = 0x0003 +_M_ESTOP = 0x0004 +_M_ENABLE = 0x0006 +_M_PP_TARGET_H = 0x0010 # Point-to-point (absolute) mode +_M_PP_TARGET_L = 0x0011 +_M_PP_INIT_SPD = 0x0012 +_M_PP_RUN_SPD = 0x0013 +_M_PP_ACCEL = 0x0014 +_M_PP_TOL = 0x0015 +_M_HOME = 0x001F +_M_FW_STEPS_H = 0x0040 # Forward (relative) mode +_M_FW_STEPS_L = 0x0041 +_M_FW_INIT_SPD = 0x0042 +_M_FW_RUN_SPD = 0x0043 +_M_FW_ACCEL = 0x0044 +_M_FW_TOL = 0x0045 + +# Gripper register addresses +_G_INIT = 0x0100 +_G_FORCE = 0x0101 +_G_TARGET_POS = 0x0103 +_G_SPEED = 0x0104 +_G_INIT_STATE = 0x0200 +_G_GRIP_STATE = 0x0201 +_G_ACTUAL_POS = 0x0202 + +# Motor status map +_MOTOR_STATUS = {0: "Idle", 1: "Busy", 2: "Stopped", 3: "LimitPos", 4: "LimitNeg"} + + +# ═══════════════════════════════════════════════════════════════════ +# Main workstation class +# ═══════════════════════════════════════════════════════════════════ + +@device( + id="electrolytic_cell_gripper", + category=["custom", "electrolytic_cell_gripper"], + description="电解池夹爪工作站", + display_name="电解池夹爪", +) +class ElectrolyticCellGripper: + """ + Electrolytic Cell Gripper Workstation (电解池夹爪). + + Combines: + - Motor 1 (slave_id=1): Horizontal slide + - Motor 2 (slave_id=2): Vertical slide + - Gripper (slave_id=5): DH PGE parallel gripper + + Exposes two high-level actions: + - pick_sample(): Grab a sample from the cell + - place_sample(): Put the sample back + + All motion parameters are hardcoded per the validated workflow. + """ + + _ros_node: "BaseROS2DeviceNode" + + # Motor speed/accel: user confirmed 5000 = register raw value in debug software + MOTOR_SPEED = 5000 # register raw value + MOTOR_ACCEL = 5000 # register raw value (acceleration time) + MOTOR_INIT_SPD = 50 # initial speed register raw value + MOTOR_TOL = 100 # tolerance in steps + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and "id" in kwargs: + device_id = kwargs.pop("id") + if config is None and "config" in kwargs: + config = kwargs.pop("config") + + self.device_id = device_id or "electrolytic_cell_gripper" + self.config = config or {} + self.logger = logging.getLogger(f"ECG.{self.device_id}") + + # ── Config ────────────────────────────────────────────── + self._port_name: str = self.config.get("port", "COM29") + self._baudrate: int = int(self.config.get("baudrate", 115200)) + self._timeout: float = float(self.config.get("timeout", 0.5)) + + self._motor1_id: int = int(self.config.get("motor1_slave_id", 1)) + self._motor2_id: int = int(self.config.get("motor2_slave_id", 2)) + self._gripper_id: int = int(self.config.get("gripper_slave_id", 5)) + + self._ser: Optional[Serial] = None + self._bus: Optional[_ModbusRTU] = None + + # ── Data store ────────────────────────────────────────── + self.data: Dict[str, Any] = { + "status": "Idle", + } + + # ── Framework hooks ───────────────────────────────────────── + + async def _sleep(self, seconds: float): + if getattr(self, "_ros_node", None) is not None: + await self._ros_node.sleep(seconds) + else: + time_module.sleep(seconds) + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + def _ensure_serial(self) -> bool: + """ + Lazy serial initialization. + If serial is already open, return True. + If not, try to open it now. This ensures the serial port is available + regardless of whether the framework called initialize() or not. + """ + if self._bus is not None and self._ser is not None and self._ser.is_open: + return True + + self.logger.info(f"Opening serial port {self._port_name} @ {self._baudrate}...") + try: + if Serial is None: + self.logger.error("pyserial not installed") + return False + + self._ser = Serial( + port=self._port_name, + baudrate=self._baudrate, + bytesize=serial.EIGHTBITS, + parity=serial.PARITY_NONE, + stopbits=serial.STOPBITS_ONE, + timeout=self._timeout, + ) + + if not self._ser.is_open: + self.logger.error(f"Failed to open {self._port_name}") + return False + + self._bus = _ModbusRTU(self._ser, self.logger) + self.logger.info(f"Serial {self._port_name} opened successfully") + return True + + except Exception as e: + self.logger.error(f"Failed to open serial: {e}") + return False + + @action() + async def initialize(self) -> bool: + """Open serial port and verify communication.""" + self.logger.info("initialize() called") + ok = self._ensure_serial() + if ok: + self.data["status"] = "Idle" + self.logger.info("initialize() SUCCESS — serial is open") + else: + self.data["status"] = "Error" + self.logger.error("initialize() FAILED — could not open serial") + return ok + + @action() + async def cleanup(self) -> bool: + """Close serial port.""" + if self._ser and self._ser.is_open: + self._ser.close() + self._ser = None + self._bus = None + self.data["status"] = "Offline" + return True + + # ── Properties ────────────────────────────────────────────── + + @property + @topic_config() + def status(self) -> str: + return self.data.get("status", "Idle") + + # ── Internal motor helpers ────────────────────────────────── + + def _motor_set_position_zero(self, slave_id: int) -> bool: + """Write 0 to actual position registers (set current position as zero).""" + return self._bus.write_multiple(slave_id, _M_POS_H, [0, 0]) + + def _motor_move_absolute(self, slave_id: int, position: int, + speed: int = None, accel: int = None) -> bool: + """ + Move motor to absolute position using point-to-point mode. + Args: + position: target in steps (signed 32-bit) + speed: register raw value (default: MOTOR_SPEED=5000) + accel: register raw value (default: MOTOR_ACCEL=5000) + """ + spd = speed if speed is not None else self.MOTOR_SPEED + acc = accel if accel is not None else self.MOTOR_ACCEL + pos_h, pos_l = _from_signed32(int(position)) + values = [pos_h, pos_l, self.MOTOR_INIT_SPD, spd, acc, self.MOTOR_TOL] + return self._bus.write_multiple(slave_id, _M_PP_TARGET_H, values) + + def _motor_read_status(self, slave_id: int) -> Optional[Dict]: + """Read motor status, position, speed.""" + regs = self._bus.read_registers(slave_id, _M_STATUS, 4) + if regs is None or len(regs) < 4: + return None + return { + "status_code": regs[0], + "status": _MOTOR_STATUS.get(regs[0], f"Unknown({regs[0]})"), + "position": _to_signed32(regs[1], regs[2]), + "speed_reg": regs[3], + } + + def _motor_emergency_stop(self, slave_id: int) -> bool: + """Send emergency stop to motor.""" + return self._bus.write_single(slave_id, _M_ESTOP, 0x0001) + + async def _motor_wait_idle(self, slave_id: int, timeout: float = 120.0, + poll_interval: float = 0.3) -> bool: + """Wait until motor status returns to Idle (0) or non-running state.""" + elapsed = 0.0 + motor_name = f"Motor{slave_id}" + while elapsed < timeout: + info = self._motor_read_status(slave_id) + if info is not None: + code = info["status_code"] + if code != 1: # Not "Busy" + self.logger.info(f"{motor_name} idle: pos={info['position']}, status={info['status']}") + return True + await self._sleep(poll_interval) + elapsed += poll_interval + self.logger.warning(f"{motor_name} wait_idle timed out after {timeout}s") + return False + + # ── Internal gripper helpers ──────────────────────────────── + + def _gripper_init(self) -> bool: + """Send homing command (0x01) to gripper.""" + return self._bus.write_single(self._gripper_id, _G_INIT, 0x01) + + async def _gripper_wait_init(self, timeout: float = 30.0) -> bool: + """Wait for gripper initialization to complete.""" + elapsed = 0.0 + while elapsed < timeout: + regs = self._bus.read_registers(self._gripper_id, _G_INIT_STATE, 1) + if regs is not None and regs[0] == 1: + self.logger.info("Gripper init complete") + return True + await self._sleep(0.5) + elapsed += 0.5 + self.logger.warning("Gripper init timed out") + return False + + def _gripper_set_force(self, force: int) -> bool: + force = max(20, min(100, force)) + return self._bus.write_single(self._gripper_id, _G_FORCE, force) + + def _gripper_set_speed(self, speed: int) -> bool: + speed = max(1, min(100, speed)) + return self._bus.write_single(self._gripper_id, _G_SPEED, speed) + + def _gripper_set_position(self, position: int) -> bool: + """Set gripper target position. 0=fully closed, 1000=fully open.""" + position = max(0, min(1000, position)) + return self._bus.write_single(self._gripper_id, _G_TARGET_POS, position) + + async def _gripper_wait_done(self, timeout: float = 15.0) -> bool: + """Wait for gripper to finish moving (grip_state != 0).""" + elapsed = 0.0 + while elapsed < timeout: + regs = self._bus.read_registers(self._gripper_id, _G_GRIP_STATE, 1) + if regs is not None and regs[0] in (1, 2, 3): + state_names = {1: "Reached", 2: "Gripped", 3: "Dropped"} + self.logger.info(f"Gripper done: {state_names.get(regs[0], regs[0])}") + return True + await self._sleep(0.2) + elapsed += 0.2 + self.logger.warning("Gripper wait timed out") + return False + + # ═══════════════════════════════════════════════════════════════ + # ACTION 1: 夹取样品 (Pick Sample) + # ═══════════════════════════════════════════════════════════════ + + @action() + async def pick_sample(self): + """ + 夹取样品 — 完整序列: + 1. 夹爪初始化 + 2. 设置夹爪力 50% + 3. 设置夹爪速度 100% + 4. 两个电机设置当前位置为零点 + 5. 1号电机移动到 838000 步 (speed=5000, accel=5000) + 6. 2号电机移动到 -800000 步 + 7. 夹爪闭合 + 8. 2号电机移动到 0 步 + 9. 1号电机移动到 0 步 + 10. 2号电机移动到 -630000 步 + """ + # ── Lazy serial open ──────────────────────────────────── + if not self._ensure_serial(): + self.logger.error("pick_sample ABORTED: cannot open serial port") + self.data["status"] = "Error" + return + + self.data["status"] = "Busy" + self.logger.info("=" * 60) + self.logger.info("pick_sample START") + self.logger.info("=" * 60) + + try: + # Step 1: Gripper init (homing) + self.logger.info("[1/11] Gripper init (homing)...") + self._gripper_init() + await self._gripper_wait_init(timeout=30.0) + + # Step 2: Set gripper force 50% + self.logger.info("[2/11] Set gripper force = 50%") + self._gripper_set_force(50) + time_module.sleep(0.05) + + # Step 3: Set gripper speed 100% + self.logger.info("[3/11] Set gripper speed = 100%") + self._gripper_set_speed(100) + time_module.sleep(0.05) + + # Step 4: Both motors set current position as zero + self.logger.info("[4/11] Motor1 + Motor2 set position zero") + self._motor_set_position_zero(self._motor1_id) + time_module.sleep(0.05) + self._motor_set_position_zero(self._motor2_id) + time_module.sleep(0.05) + + # Step 5: Motor 1 move to 838000 + self.logger.info("[5/11] Motor1 move to 838000 steps (speed=5000, accel=5000)") + self._motor_move_absolute(self._motor1_id, 838000, speed=5000, accel=5000) + await self._motor_wait_idle(self._motor1_id, timeout=120.0) + + # Step 6: Motor 2 move to -800000 + self.logger.info("[6/11] Motor2 move to -800000 steps") + self._motor_move_absolute(self._motor2_id, -800000, speed=5000, accel=5000) + await self._motor_wait_idle(self._motor2_id, timeout=120.0) + + # Step 7: Gripper close (position=0) + self.logger.info("[7/11] Gripper close") + self._gripper_set_position(0) + await self._gripper_wait_done(timeout=15.0) + + # Step 8: Motor 2 move to 0 + self.logger.info("[8/11] Motor2 move to 0 steps") + self._motor_move_absolute(self._motor2_id, 0, speed=5000, accel=5000) + await self._motor_wait_idle(self._motor2_id, timeout=120.0) + + # Step 9: Motor 1 move to 0 + self.logger.info("[9/11] Motor1 move to 0 steps") + self._motor_move_absolute(self._motor1_id, 0, speed=5000, accel=5000) + await self._motor_wait_idle(self._motor1_id, timeout=120.0) + + # Step 10: Motor 2 move to -850000 + # self.logger.info("[10/11] Motor2 move to -850000 steps") + # self._motor_move_absolute(self._motor2_id, -850000, speed=5000, accel=5000) + self.logger.info("[10/11] Motor2 move to -630000 steps") + self._motor_move_absolute(self._motor2_id, -630000, speed=5000, accel=5000) + await self._motor_wait_idle(self._motor2_id, timeout=120.0) + + self.data["status"] = "Idle" + self.logger.info("=" * 60) + self.logger.info("pick_sample COMPLETE") + self.logger.info("=" * 60) + + except Exception as e: + self.logger.error(f"pick_sample failed: {e}") + self.data["status"] = "Error" + + # ═══════════════════════════════════════════════════════════════ + # ACTION 2: 放下样品 (Place Sample) + # ═══════════════════════════════════════════════════════════════ + + @action() + async def place_sample(self): + """ + 放下样品 — 完整序列: + 1. 2号电机移动到 0 步 + 2. 1号电机移动到 838000 步 + 3. 2号电机移动到 -790000 步 + 4. 夹爪张开 + 5. 2号电机移动到 0 步 + 6. 1号电机移动到 0 步 + """ + # ── Lazy serial open ──────────────────────────────────── + if not self._ensure_serial(): + self.logger.error("place_sample ABORTED: cannot open serial port") + self.data["status"] = "Error" + return + + self.data["status"] = "Busy" + self.logger.info("=" * 60) + self.logger.info("place_sample START") + self.logger.info("=" * 60) + + try: + # Step 1: Motor 2 move to 0 + self.logger.info("[1/6] Motor2 move to 0 steps") + self._motor_move_absolute(self._motor2_id, 0, speed=5000, accel=5000) + await self._motor_wait_idle(self._motor2_id, timeout=120.0) + + # Step 2: Motor 1 move to 838000 + self.logger.info("[2/6] Motor1 move to 838000 steps") + self._motor_move_absolute(self._motor1_id, 838000, speed=5000, accel=5000) + await self._motor_wait_idle(self._motor1_id, timeout=120.0) + + # Step 3: Motor 2 move to -790000 + self.logger.info("[3/6] Motor2 move to -790000 steps") + self._motor_move_absolute(self._motor2_id, -790000, speed=5000, accel=5000) + await self._motor_wait_idle(self._motor2_id, timeout=120.0) + + # Step 4: Gripper open (position=1000) + self.logger.info("[4/6] Gripper open") + self._gripper_set_position(1000) + await self._gripper_wait_done(timeout=15.0) + + # Step 5: Motor 2 move to 0 + self.logger.info("[5/6] Motor2 move to 0 steps") + self._motor_move_absolute(self._motor2_id, 0, speed=5000, accel=5000) + await self._motor_wait_idle(self._motor2_id, timeout=120.0) + + # Step 6: Motor 1 move to 0 + self.logger.info("[6/6] Motor1 move to 0 steps") + self._motor_move_absolute(self._motor1_id, 0, speed=5000, accel=5000) + await self._motor_wait_idle(self._motor1_id, timeout=120.0) + + self.data["status"] = "Idle" + self.logger.info("=" * 60) + self.logger.info("place_sample COMPLETE") + self.logger.info("=" * 60) + + except Exception as e: + self.logger.error(f"place_sample failed: {e}") + self.data["status"] = "Error" + + # ═══════════════════════════════════════════════════════════════ + # Emergency stop + # ═══════════════════════════════════════════════════════════════ + + @action() + async def emergency_stop(self): + """Emergency stop all motors immediately.""" + self.logger.warning("EMERGENCY STOP") + if self._bus is not None: + self._motor_emergency_stop(self._motor1_id) + time_module.sleep(0.02) + self._motor_emergency_stop(self._motor2_id) + self.data["status"] = "Stopped" diff --git a/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.yaml b/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.yaml new file mode 100644 index 0000000..976f633 --- /dev/null +++ b/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.yaml @@ -0,0 +1,185 @@ +electrolytic_cell_gripper: + action_value_mappings: + emergency_stop: + description: 紧急停止所有电机 + goal: {} + result: + success: success + type: SendCmd + pick_sample: + description: 夹取样品 — 初始化夹爪→电机归零→移动到位→夹取→收回 + goal: {} + result: + success: success + type: SendCmd + place_sample: + description: 放下样品 — 移动到位→张开夹爪→收回 + goal: {} + result: + success: success + type: SendCmd + category: + - custom + - electrolytic_cell_gripper + class: + action_value_mappings: + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-emergency_stop: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: emergency_stop参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-pick_sample: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: pick_sample参数 + type: object + type: UniLabJsonCommandAsync + auto-place_sample: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: place_sample参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + module: device_package_example.devices.electrolytic_cell_gripper.electrolytic_cell_gripper:ElectrolyticCellGripper + status_types: + status: str + type: python + config_info: [] + description: '' + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + status: + type: string + required: + - status + type: object + status_types: + status: + default: Idle + description: 'Workstation status: Idle / Busy / Stopped / Error / Offline' + type: str + version: 1.0.0 diff --git a/device_package_example/devices/electrolytic_cell_gripper/graph_example_electrolytic_cell_gripper.json b/device_package_example/devices/electrolytic_cell_gripper/graph_example_electrolytic_cell_gripper.json new file mode 100644 index 0000000..12cef3c --- /dev/null +++ b/device_package_example/devices/electrolytic_cell_gripper/graph_example_electrolytic_cell_gripper.json @@ -0,0 +1,22 @@ +{ + "nodes": [ + { + "id": "electrolytic_cell_gripper_1", + "name": "电解池夹爪", + "children": [], + "parent": null, + "type": "device", + "class": "electrolytic_cell_gripper", + "position": {"x": 0, "y": 0, "z": 0}, + "config": { + "port": "COM29", + "baudrate": 115200, + "timeout": 0.5, + "motor1_slave_id": 1, + "motor2_slave_id": 2, + "gripper_slave_id": 5 + }, + "data": {} + } + ] +} diff --git a/device_package_example/devices/hk_a0/hk_a0.yaml b/device_package_example/devices/hk_a0/hk_a0.yaml index 0bc2a25..b5880f8 100644 --- a/device_package_example/devices/hk_a0/hk_a0.yaml +++ b/device_package_example/devices/hk_a0/hk_a0.yaml @@ -99,7 +99,7 @@ hk_a0: title: stop_all参数 type: object type: UniLabJsonCommandAsync - module: unilabos.devices.custom.hk_a0:HKA0 + module: device_package_example.devices.hk_a0.hk_a0:HKA0 status_types: outputs: String status: str diff --git a/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml index 9de4121..d82dc2e 100644 --- a/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml +++ b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml @@ -2,7 +2,7 @@ jyhsm_temperature_transmitter: category: - sensor class: - module: unilabos.devices.sensor.jyhsm_temperature_transmitter:JyhsmTemperatureTransmitter + module: device_package_example.devices.jyhsm_temperature_transmitter.jyhsm_temperature_transmitter:JyhsmTemperatureTransmitter type: python status_types: status: str diff --git a/device_package_example/devices/longer_bt100/longer_bt100.py b/device_package_example/devices/longer_bt100/longer_bt100.py index 4afa672..e17f721 100644 --- a/device_package_example/devices/longer_bt100/longer_bt100.py +++ b/device_package_example/devices/longer_bt100/longer_bt100.py @@ -9,7 +9,10 @@ import time as time_module from typing import Dict, Any, Optional -import serial +try: + import serial +except ImportError: + serial = None try: from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode diff --git a/device_package_example/devices/longer_bt100/longer_bt100.yaml b/device_package_example/devices/longer_bt100/longer_bt100.yaml index 563165d..aca2e17 100644 --- a/device_package_example/devices/longer_bt100/longer_bt100.yaml +++ b/device_package_example/devices/longer_bt100/longer_bt100.yaml @@ -239,7 +239,7 @@ longer_bt100: title: stop参数 type: object type: UniLabJsonCommandAsync - module: unilabos.devices.pump_and_valve.longer_bt100:LongerBT100 + module: device_package_example.devices.longer_bt100.longer_bt100:LongerBT100 status_types: direction: str is_fullspeed: bool diff --git a/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py b/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py index 7c2cda7..7901a89 100644 --- a/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py +++ b/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py @@ -12,7 +12,10 @@ import logging import asyncio -import serial +try: + import serial +except ImportError: + serial = None import time as time_module from typing import Dict, Any, Optional @@ -251,8 +254,8 @@ def max_velocity(self) -> float: return self.data.get("max_velocity", 0.5) @property - def mode(self) -> int: - return self.data.get("mode", 0) + def mode(self) -> float: + return float(self.data.get("mode", 0)) @property def plunger_position(self) -> str: diff --git a/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.yaml b/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.yaml index f321c9a..9a04525 100644 --- a/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.yaml +++ b/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.yaml @@ -1,6 +1,6 @@ runze_sy03b_t08: class: - module: unilab_ext.devices.runze_sy03b_t08:RunzeSY03BT08 + module: device_package_example.devices.runze_sy03b_t08.runze_sy03b_t08:RunzeSY03BT08 type: python config_schema: type: object diff --git a/device_package_example/devices/solenoid_valve_4v110/graph_example_solenoid_valve_4v110.json b/device_package_example/devices/solenoid_valve_4v110/graph_example_solenoid_valve_4v110.json new file mode 100644 index 0000000..d03831f --- /dev/null +++ b/device_package_example/devices/solenoid_valve_4v110/graph_example_solenoid_valve_4v110.json @@ -0,0 +1,18 @@ +{ + "nodes": [ + { + "id": "solenoid_valve_4v110_1", + "name": "亚德客 4V110-06 电磁阀", + "children": [], + "parent": null, + "type": "device", + "class": "solenoid_valve_4v110", + "position": {"x": 400, "y": 200, "z": 0}, + "config": { + "port": "COM14", + "baudrate": 9600 + }, + "data": {} + } + ] +} diff --git a/device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.py b/device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.py new file mode 100644 index 0000000..ba0a023 --- /dev/null +++ b/device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.py @@ -0,0 +1,234 @@ +""" +亚德客 4V110-06 DC24V 电磁阀驱动 +通过 Arduino Uno GPIO + 继电器模块控制(复用 CNI 激光器 Arduino) +通信方式:串口 ASCII 指令 + +接线: + Arduino D7 → 继电器模块 IN + Arduino 5V → 继电器模块 VCC + Arduino GND → 继电器模块 GND + 继电器 COM → 24V DC (+) + 继电器 NO → 电磁阀线圈+ (红) + 电磁阀线圈- (黑) → 24V DC GND (-) +""" + +import logging +import time as time_module +from typing import Dict, Any + +try: + import serial +except ImportError: + serial = None + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="solenoid_valve_4v110", + category=["pump_and_valve", "solenoid_valve_4v110"], + description="亚德客 4V110-06 DC24V 电磁阀,Arduino 串口控制", + display_name="4V110 电磁阀", +) +class SolenoidValve4V110: + """亚德客 4V110-06 DC24V 二位五通电磁阀 + + 通过 Arduino Uno 的 GPIO D7 驱动继电器模块,控制 24V 线圈通断。 + 串口 ASCII 指令协议: + VALVE ON\\n → 打开电磁阀(D7 HIGH → 继电器吸合 → 线圈通电) + VALVE OFF\\n → 关闭电磁阀(D7 LOW → 继电器释放 → 线圈断电 → 弹簧复位) + VALVE?\\n → 查询状态,返回 "VALVE:ON" 或 "VALVE:OFF" + """ + + _ros_node: "BaseROS2DeviceNode" + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + # --- 标准 init 模式 --- + if device_id is None and 'id' in kwargs: + device_id = kwargs.pop('id') + if config is None and 'config' in kwargs: + config = kwargs.pop('config') + + self.device_id = device_id or "solenoid_valve_4v110" + self.config = config or {} + self.logger = logging.getLogger(f"SolenoidValve4V110.{self.device_id}") + + # --- self.data 必须预填充所有 @property 字段 --- + self.data = { + "status": "Idle", + "valve_position": "Closed", + } + + # --- 串口配置(从 config 或 kwargs 双重读取)--- + self._port = self.config.get("port") or kwargs.get("port", "COM3") + self._baudrate = int(self.config.get("baudrate") or kwargs.get("baudrate", 9600)) + self._timeout = float(self.config.get("timeout") or kwargs.get("timeout", 1)) + + self.ser = None + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + def _open_serial(self) -> bool: + if self.ser is not None and self.ser.is_open: + return True + if serial is None: + self.logger.error("pyserial 未安装") + return False + try: + self.ser = serial.Serial( + port=self._port, + baudrate=self._baudrate, + timeout=self._timeout, + ) + self.logger.info(f"Serial connected: {self._port} @ {self._baudrate}") + return True + except Exception as e: + self.logger.error(f"Failed to open serial port {self._port}: {e}") + self.ser = None + return False + + @action(description="初始化设备") + async def initialize(self) -> bool: + """初始化:打开串口并确保电磁阀处于关闭状态""" + if not self._open_serial(): + self.data["status"] = "Offline" + return False + self._send_command("VALVE OFF") + self.data["status"] = "Idle" + self.data["valve_position"] = "Closed" + self.logger.info("Initialized: valve closed") + return True + + @action(description="清理资源") + async def cleanup(self) -> bool: + """清理:关闭电磁阀并释放串口""" + try: + self._send_command("VALVE OFF") + self.data["valve_position"] = "Closed" + except Exception: + pass + self.data["status"] = "Offline" + if self.ser and self.ser.is_open: + self.ser.close() + self.logger.info("Cleanup complete") + return True + + # ========== 通信辅助 ========== + + def _send_command(self, cmd: str) -> str: + """发送 ASCII 指令到 Arduino,返回响应""" + if self.ser is None or not self.ser.is_open: + self.logger.warning(f"Serial not available, dry-run: {cmd}") + return "" + try: + self.ser.reset_input_buffer() + self.ser.write(f"{cmd}\n".encode("ascii")) + time_module.sleep(0.05) # 等待 Arduino 处理 + response = self.ser.readline().decode("ascii", errors="ignore").strip() + self.logger.debug(f"TX: {cmd} → RX: {response}") + return response + except Exception as e: + self.logger.error(f"Serial communication error: {e}") + return "" + + # ========== 电磁阀标准动作(对齐已有接口)========== + + @action(description="打开电磁阀") + async def open(self, **kwargs) -> bool: + """打开电磁阀(线圈通电,阀芯换向)""" + if not self._open_serial(): + return False + self.data["status"] = "Busy" + resp = self._send_command("VALVE ON") + ok = "ON" in resp.upper() if resp else False + self.data["valve_position"] = "Open" if ok else "Closed" + self.data["status"] = "Idle" if ok else "Error" + self.logger.info("Valve opened" if ok else f"Valve open failed: {resp}") + return ok + + @action(description="关闭电磁阀") + async def close(self, **kwargs) -> bool: + """关闭电磁阀(线圈断电,弹簧复位)""" + if not self._open_serial(): + return False + self.data["status"] = "Busy" + resp = self._send_command("VALVE OFF") + ok = "OFF" in resp.upper() if resp else False + self.data["valve_position"] = "Closed" if ok else self.data["valve_position"] + self.data["status"] = "Idle" if ok else "Error" + self.logger.info("Valve closed" if ok else f"Valve close failed: {resp}") + return ok + + @action(description="设置阀门位置") + async def set_valve_position(self, position, **kwargs) -> bool: + """设置阀门位置。参数名必须是 position(接口契约) + + Args: + position: "Open" 或 "Closed" + """ + pos_str = str(position).strip().lower() + if pos_str in ("open", "1", "on", "true"): + return await self.open() + elif pos_str in ("closed", "close", "0", "off", "false"): + return await self.close() + else: + self.logger.warning(f"Unknown valve position: {position}, closing for safety") + return await self.close() + + @action(description="查询电磁阀是否打开", always_free=True) + async def is_open(self, **kwargs) -> bool: + """检查电磁阀是否打开""" + resp = self._send_command("VALVE?") + if "ON" in resp.upper(): + self.data["valve_position"] = "Open" + return True + elif "OFF" in resp.upper(): + self.data["valve_position"] = "Closed" + return False + # 若无法通信,依据本地状态 + return self.data.get("valve_position", "Closed") == "Open" + + @action(description="查询电磁阀是否关闭", always_free=True) + async def is_closed(self, **kwargs) -> bool: + """检查电磁阀是否关闭""" + return not await self.is_open() + + @action(description="发送自定义串口指令") + async def send_command(self, command: str, **kwargs) -> str: + """发送自定义指令(对齐已有接口)""" + return self._send_command(str(command)) + + # ========== 属性(@property)========== + + @property + @topic_config() + def status(self) -> str: + return self.data.get("status", "Idle") + + @property + @topic_config() + def valve_position(self) -> str: + return self.data.get("valve_position", "Closed") diff --git a/device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.yaml b/device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.yaml new file mode 100644 index 0000000..7da3145 --- /dev/null +++ b/device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.yaml @@ -0,0 +1,236 @@ +solenoid_valve_4v110: + category: + - pump_and_valve + - solenoid_valve_4v110 + class: + action_value_mappings: + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-close: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: close参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-is_closed: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: is_closed参数 + type: object + type: UniLabJsonCommandAsync + auto-is_open: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: is_open参数 + type: object + type: UniLabJsonCommandAsync + auto-open: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: open参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-send_command: + feedback: {} + goal: {} + goal_default: + command: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + command: + type: string + required: + - command + type: object + result: {} + required: + - goal + title: send_command参数 + type: object + type: UniLabJsonCommandAsync + auto-set_valve_position: + feedback: {} + goal: {} + goal_default: + position: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + position: + type: string + required: + - position + type: object + result: {} + required: + - goal + title: set_valve_position参数 + type: object + type: UniLabJsonCommandAsync + module: device_package_example.devices.solenoid_valve_4v110.solenoid_valve_4v110:SolenoidValve4V110 + status_types: + status: str + valve_position: str + type: python + config_info: [] + description: 亚德客 4V110-06 DC24V 二位五通电磁阀 (Arduino + 继电器控制) + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + status: + type: string + valve_position: + type: string + required: + - status + - valve_position + type: object + version: 1.0.0 diff --git a/device_package_example/devices/xyz_guangdian/xyz_guangdian.py b/device_package_example/devices/xyz_guangdian/xyz_guangdian.py index 3c38f87..fb24ad7 100644 --- a/device_package_example/devices/xyz_guangdian/xyz_guangdian.py +++ b/device_package_example/devices/xyz_guangdian/xyz_guangdian.py @@ -314,9 +314,9 @@ def push_rod_status(self) -> str: return self.data.get("push_rod_status", "released") @property - def error_code(self) -> int: + def error_code(self) -> float: """错误代码""" - return self.data.get("error_code", 0) + return float(self.data.get("error_code", 0)) # ========== 动作方法 ========== diff --git a/device_package_example/devices/xyz_guangdian/xyz_guangdian.yaml b/device_package_example/devices/xyz_guangdian/xyz_guangdian.yaml index f74ee97..e162fc6 100644 --- a/device_package_example/devices/xyz_guangdian/xyz_guangdian.yaml +++ b/device_package_example/devices/xyz_guangdian/xyz_guangdian.yaml @@ -438,7 +438,7 @@ xyz_guangdian: title: stop_all参数 type: object type: UniLabJsonCommandAsync - module: unilabos.devices.workstation.xyz_guangdian:XYZGuangdian + module: device_package_example.devices.xyz_guangdian.xyz_guangdian:XYZGuangdian status_types: error_code: int is_enabled: bool diff --git a/device_package_example/devices/zolix_omni_lambda/graph_example_zolix_omni_lambda.json b/device_package_example/devices/zolix_omni_lambda/graph_example_zolix_omni_lambda.json new file mode 100644 index 0000000..933ec95 --- /dev/null +++ b/device_package_example/devices/zolix_omni_lambda/graph_example_zolix_omni_lambda.json @@ -0,0 +1,19 @@ +{ + "nodes": [ + { + "id": "zolix_omni_lambda_1", + "name": "Zolix Omni-λ 光谱仪", + "children": [], + "parent": null, + "type": "device", + "class": "zolix_omni_lambda", + "position": {"x": 0, "y": 0, "z": 0}, + "config": { + "port": "COM11", + "baudrate": 19200, + "timeout": 5 + }, + "data": {} + } + ] +} diff --git a/device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.py b/device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.py new file mode 100644 index 0000000..8ccb3aa --- /dev/null +++ b/device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.py @@ -0,0 +1,662 @@ +import logging +import time as time_module +from typing import Dict, Any, Optional + +try: + import serial +except ImportError: + serial = None + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="zolix_omni_lambda", + category=["custom", "zolix_omni_lambda"], + description="Zolix Omni-λ 单色仪/光谱仪", + display_name="Zolix Omni-λ", +) +class ZolixOmniLambda: + """Zolix Omni-λ 单色仪/光谱仪驱动 + + 通信协议: Serial (USB/RS232), ASCII 文本指令, \\r 结束符 + 默认波特率: 19200, 8N1 + 指令格式: " [参数]\\r" + 响应格式: ASCII 文本, 以 "OK" 或 "Exx" 结尾 + + 支持功能: + - 波长绝对/相对移动 (nm) + - 波数绝对移动 (cm⁻¹) + - 光栅切换与查询 + - 光栅台切换 + - 出入口切换 + - 系统信息查询 + - IO 端口控制 + """ + + _ros_node: "BaseROS2DeviceNode" + + # ---------- 错误码映射 ---------- + ERROR_CODES = { + "E01": "Command not recognized", + "E02": "Parameter out of range", + "E03": "Device busy", + "E04": "Communication error", + "E05": "Hardware error", + "E06": "Timeout", + } + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and 'id' in kwargs: + device_id = kwargs.pop('id') + if config is None and 'config' in kwargs: + config = kwargs.pop('config') + + self.device_id = device_id or "unknown_device" + self.config = config or {} + self.logger = logging.getLogger(f"ZolixOmniLambda.{self.device_id}") + + # self.data 必须预填充所有 @property 对应的字段 + self.data: Dict[str, Any] = { + "status": "Offline", + "wavelength": 0.0, + "wavenumber": 0.0, + "grating": "1", + "turret": "1", + "exit_port": "0", + "entrance_port": "0", + "system_info": "", + } + + # 串口配置 — 同时从 config 和 kwargs 中查找,兼容框架不同传参方式 + self._port = self.config.get("port") or kwargs.get("port", "COM11") + self._baudrate = int(self.config.get("baudrate") or kwargs.get("baudrate", 19200)) + self._timeout = float(self.config.get("timeout") or kwargs.get("timeout", 5)) + self._ser: Optional[Any] = None + + self.logger.info(f"Config received: config={self.config}, kwargs_keys={list(kwargs.keys())}, using port={self._port}") + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + # ========== 通信层 ========== + + def _connect(self): + """打开串口连接""" + if serial is None: + raise ImportError("pyserial is required. Install with: pip install pyserial") + if self._ser is not None and self._ser.is_open: + return + self._ser = serial.Serial( + port=self._port, + baudrate=self._baudrate, + bytesize=serial.EIGHTBITS, + parity=serial.PARITY_NONE, + stopbits=serial.STOPBITS_ONE, + timeout=self._timeout, + ) + self.logger.info(f"Serial port opened: {self._port} @ {self._baudrate}") + + def _disconnect(self): + """关闭串口连接""" + if self._ser is not None and self._ser.is_open: + self._ser.close() + self.logger.info("Serial port closed") + self._ser = None + + def _send_command(self, cmd: str, timeout: float = None) -> str: + """发送 ASCII 指令并读取响应 + + 指令格式: "COMMAND [params]\\r" + 响应: 读取直到 "OK\\r" 或 "Exx\\r" 或超时 + + Args: + cmd: 指令字符串 (不含 \\r) + timeout: 可选超时覆盖 (秒) + + Returns: + 响应字符串 (去除前导垃圾字节后) + """ + if self._ser is None or not self._ser.is_open: + self._connect() + + # 清空接收缓冲区 + self._ser.reset_input_buffer() + + # 发送指令 + full_cmd = f"{cmd}\r" + self._ser.write(full_cmd.encode("ascii")) + self.logger.debug(f"TX: {cmd}") + + # 读取响应 — 使用 buffer 累积 + 关键字匹配 + effective_timeout = timeout if timeout is not None else self._timeout + buffer = "" + start_time = time_module.time() + + while time_module.time() - start_time < effective_timeout: + if self._ser.in_waiting > 0: + chunk = self._ser.read(self._ser.in_waiting).decode("ascii", errors="replace") + buffer += chunk + + # 检查是否收到完整响应 (以 OK 或 Exx 结尾) + stripped = buffer.strip() + if stripped.endswith("OK"): + break + for code in self.ERROR_CODES: + if stripped.endswith(code): + break + else: + time_module.sleep(0.05) + continue + break + else: + time_module.sleep(0.05) + + self.logger.debug(f"RX: {buffer.strip()}") + return buffer.strip() + + def _parse_response(self, response: str) -> Dict[str, Any]: + """解析响应字符串 + + Returns: + {"success": bool, "data": str, "error": str or None} + """ + if not response: + return {"success": False, "data": "", "error": "No response (timeout)"} + + # 检查错误码 + for code, desc in self.ERROR_CODES.items(): + if code in response: + return {"success": False, "data": response, "error": f"{code}: {desc}"} + + if "OK" in response: + # 提取 OK 之前的数据部分 + idx = response.rfind("OK") + data_part = response[:idx].strip() + return {"success": True, "data": data_part, "error": None} + + # 没有明确的 OK 或 Exx,视为数据响应 + return {"success": True, "data": response, "error": None} + + def _wait_until_idle(self, timeout: float = 120.0): + """轮询等待设备完成移动 (同步方法, 在底层串口通信中使用)""" + start = time_module.time() + while time_module.time() - start < timeout: + resp = self._send_command("POSITION?") + parsed = self._parse_response(resp) + if parsed["success"]: + return True + if parsed.get("error", "").startswith("E03"): + time_module.sleep(0.5) + continue + time_module.sleep(0.2) + return False + + # ========== 生命周期 ========== + + @action() + async def initialize(self) -> bool: + """初始化设备: 打开串口, 发送 Hello 联络指令, 查询初始状态""" + try: + self._connect() + + # 发送 Hello 联络指令 + resp = self._send_command("Hello") + parsed = self._parse_response(resp) + if not parsed["success"]: + self.logger.warning(f"Hello command failed: {parsed['error']}") + + # 查询当前波长位置 + try: + self._do_query_position() + except Exception as e: + self.logger.warning(f"Initial position query failed: {e}") + + # 查询系统信息 + try: + self._do_query_system_info() + except Exception as e: + self.logger.warning(f"Initial system info query failed: {e}") + + self.data["status"] = "Idle" + self.logger.info("Device initialized successfully") + return True + + except Exception as e: + self.logger.error(f"Initialization failed: {e}") + self.data["status"] = "Offline" + return False + + @action() + async def cleanup(self) -> bool: + """清理资源: 关闭串口""" + try: + self._disconnect() + self.data["status"] = "Offline" + return True + except Exception as e: + self.logger.error(f"Cleanup failed: {e}") + return False + + # ========== 内部查询方法 ========== + + def _do_query_position(self): + """查询并更新当前波长位置""" + resp = self._send_command("POSITION?") + parsed = self._parse_response(resp) + if parsed["success"] and parsed["data"]: + try: + wl = float(parsed["data"]) + self.data["wavelength"] = wl + if wl > 0: + self.data["wavenumber"] = 1e7 / wl # nm -> cm⁻¹ + except (ValueError, ZeroDivisionError): + pass + + def _do_query_system_info(self): + """查询并更新系统信息""" + resp = self._send_command("SYSTEMINFO?") + parsed = self._parse_response(resp) + if parsed["success"]: + self.data["system_info"] = parsed["data"] + + # ========== 动作方法 ========== + # 注意:所有参数类型只能用 float 或 str,不能用 int + # 因为 UniLab-OS 的 action type mapping 只支持 float 和 str + + @action() + async def move_to(self, wavelength: float, **kwargs) -> Dict[str, Any]: + """绝对移动到指定波长 + + Args: + wavelength: 目标波长 (nm) + + Returns: + {"success": bool, "wavelength": float} + """ + wavelength = float(wavelength) + self.data["status"] = "Busy" + + try: + resp = self._send_command(f"MOVETO {wavelength}") + parsed = self._parse_response(resp) + + if not parsed["success"]: + self.data["status"] = "Idle" + return {"success": False, "error": parsed["error"]} + + self._wait_until_idle() + self._do_query_position() + self.data["status"] = "Idle" + return {"success": True, "wavelength": self.data["wavelength"]} + + except Exception as e: + self.logger.error(f"move_to failed: {e}") + self.data["status"] = "Idle" + return {"success": False, "error": str(e)} + + @action() + async def move_relative(self, wavelength: float, **kwargs) -> Dict[str, Any]: + """相对移动指定波长 + + Args: + wavelength: 相对移动量 (nm), 正值红移, 负值蓝移 + + Returns: + {"success": bool, "wavelength": float} + """ + wavelength = float(wavelength) + self.data["status"] = "Busy" + + try: + resp = self._send_command(f"MOVE {wavelength}") + parsed = self._parse_response(resp) + + if not parsed["success"]: + self.data["status"] = "Idle" + return {"success": False, "error": parsed["error"]} + + self._wait_until_idle() + self._do_query_position() + self.data["status"] = "Idle" + return {"success": True, "wavelength": self.data["wavelength"]} + + except Exception as e: + self.logger.error(f"move_relative failed: {e}") + self.data["status"] = "Idle" + return {"success": False, "error": str(e)} + + @action() + async def move_to_wavenumber(self, wavenumber: float, **kwargs) -> Dict[str, Any]: + """绝对移动到指定波数 + + Args: + wavenumber: 目标波数 (cm⁻¹) + + Returns: + {"success": bool, "wavenumber": float} + """ + wavenumber = float(wavenumber) + self.data["status"] = "Busy" + + try: + resp = self._send_command(f"WaveNumber_abs {wavenumber}") + parsed = self._parse_response(resp) + + if not parsed["success"]: + self.data["status"] = "Idle" + return {"success": False, "error": parsed["error"]} + + self._wait_until_idle() + self._do_query_position() + self.data["status"] = "Idle" + return {"success": True, "wavenumber": self.data["wavenumber"]} + + except Exception as e: + self.logger.error(f"move_to_wavenumber failed: {e}") + self.data["status"] = "Idle" + return {"success": False, "error": str(e)} + + @action() + async def set_grating(self, grating: str, **kwargs) -> Dict[str, Any]: + """切换光栅 + + Args: + grating: 光栅编号 (1~3) + + Returns: + {"success": bool, "grating": str} + """ + grating_val = str(grating) + self.data["status"] = "Busy" + + try: + resp = self._send_command(f"GRATING {grating_val}") + parsed = self._parse_response(resp) + + if not parsed["success"]: + self.data["status"] = "Idle" + return {"success": False, "error": parsed["error"]} + + self._wait_until_idle() + self.data["grating"] = grating_val + self.data["status"] = "Idle" + return {"success": True, "grating": grating_val} + + except Exception as e: + self.logger.error(f"set_grating failed: {e}") + self.data["status"] = "Idle" + return {"success": False, "error": str(e)} + + @action() + async def grating_home(self, **kwargs) -> Dict[str, Any]: + """光栅重新定位 (回零) + + Returns: + {"success": bool} + """ + self.data["status"] = "Busy" + + try: + resp = self._send_command("GRATINGHOME") + parsed = self._parse_response(resp) + + self._wait_until_idle(timeout=60.0) + self._do_query_position() + self.data["status"] = "Idle" + return {"success": parsed["success"], "error": parsed.get("error")} + + except Exception as e: + self.logger.error(f"grating_home failed: {e}") + self.data["status"] = "Idle" + return {"success": False, "error": str(e)} + + @action() + async def set_turret(self, turret: str, **kwargs) -> Dict[str, Any]: + """设置光栅台 + + Args: + turret: 光栅台编号 + + Returns: + {"success": bool, "turret": str} + """ + turret_val = str(turret) + self.data["status"] = "Busy" + + try: + resp = self._send_command(f"TURRET {turret_val}") + parsed = self._parse_response(resp) + + self._wait_until_idle() + self.data["turret"] = turret_val + self.data["status"] = "Idle" + return {"success": parsed["success"], "turret": turret_val, "error": parsed.get("error")} + + except Exception as e: + self.logger.error(f"set_turret failed: {e}") + self.data["status"] = "Idle" + return {"success": False, "error": str(e)} + + @action() + async def set_exit_port(self, port: str, **kwargs) -> Dict[str, Any]: + """切换出口 + + Args: + port: 出口编号 (0=前置, 1=侧面) + + Returns: + {"success": bool, "exit_port": str} + """ + port_val = str(port) + + try: + resp = self._send_command(f"EXITPORT {port_val}") + parsed = self._parse_response(resp) + + if parsed["success"]: + self.data["exit_port"] = port_val + return {"success": parsed["success"], "exit_port": port_val, "error": parsed.get("error")} + + except Exception as e: + self.logger.error(f"set_exit_port failed: {e}") + return {"success": False, "error": str(e)} + + @action() + async def set_entrance_port(self, port: str, **kwargs) -> Dict[str, Any]: + """切换入口 + + Args: + port: 入口编号 (0=前置, 1=侧面) + + Returns: + {"success": bool, "entrance_port": str} + """ + port_val = str(port) + + try: + resp = self._send_command(f"ENTRANCEPORT {port_val}") + parsed = self._parse_response(resp) + + if parsed["success"]: + self.data["entrance_port"] = port_val + return {"success": parsed["success"], "entrance_port": port_val, "error": parsed.get("error")} + + except Exception as e: + self.logger.error(f"set_entrance_port failed: {e}") + return {"success": False, "error": str(e)} + + @action() + async def stop(self, **kwargs) -> Dict[str, Any]: + """停止当前移动 + + Returns: + {"success": bool} + """ + try: + resp = self._send_command("STOP") + parsed = self._parse_response(resp) + self.data["status"] = "Idle" + return {"success": parsed["success"], "error": parsed.get("error")} + + except Exception as e: + self.logger.error(f"stop failed: {e}") + self.data["status"] = "Idle" + return {"success": False, "error": str(e)} + + @action() + async def query_position(self, **kwargs) -> Dict[str, Any]: + """查询当前波长位置 + + Returns: + {"success": bool, "wavelength": float, "wavenumber": float} + """ + try: + self._do_query_position() + return { + "success": True, + "wavelength": self.data["wavelength"], + "wavenumber": self.data["wavenumber"], + } + except Exception as e: + self.logger.error(f"query_position failed: {e}") + return {"success": False, "error": str(e)} + + @action() + async def query_system_info(self, **kwargs) -> Dict[str, Any]: + """查询系统信息 + + Returns: + {"success": bool, "system_info": str} + """ + try: + self._do_query_system_info() + return {"success": True, "system_info": self.data["system_info"]} + except Exception as e: + self.logger.error(f"query_system_info failed: {e}") + return {"success": False, "error": str(e)} + + @action() + async def query_gratings(self, **kwargs) -> Dict[str, Any]: + """查询光栅参数 + + Returns: + {"success": bool, "gratings_info": str} + """ + try: + resp = self._send_command("GRATINGS?") + parsed = self._parse_response(resp) + return {"success": parsed["success"], "gratings_info": parsed["data"], "error": parsed.get("error")} + except Exception as e: + self.logger.error(f"query_gratings failed: {e}") + return {"success": False, "error": str(e)} + + @action() + async def set_port_output(self, value: str, **kwargs) -> Dict[str, Any]: + """设置 IO 端口输出 + + Args: + value: 输出值字符串 + + Returns: + {"success": bool} + """ + try: + resp = self._send_command(f"PORT_OUTPUT {value}") + parsed = self._parse_response(resp) + return {"success": parsed["success"], "error": parsed.get("error")} + except Exception as e: + self.logger.error(f"set_port_output failed: {e}") + return {"success": False, "error": str(e)} + + @action() + async def send_command(self, command: str, **kwargs) -> Dict[str, Any]: + """发送自定义指令 + + Args: + command: 完整指令字符串 (不含 \\r) + + Returns: + {"success": bool, "response": str} + """ + try: + resp = self._send_command(str(command)) + parsed = self._parse_response(resp) + return {"success": parsed["success"], "response": parsed["data"], "error": parsed.get("error")} + except Exception as e: + self.logger.error(f"send_command failed: {e}") + return {"success": False, "error": str(e)} + + # ========== 属性 (property) ========== + # 注意:@property 返回类型只能用 float, str, bool + # 不能用 int,否则 set_ 自动生成时会触发 + # ValueError: Unsupported action type: + + @property + @topic_config() + def status(self) -> str: + return self.data.get("status", "Offline") + + @property + @topic_config() + def wavelength(self) -> float: + """当前波长 (nm)""" + return float(self.data.get("wavelength", 0.0)) + + @property + @topic_config() + def wavenumber(self) -> float: + """当前波数 (cm⁻¹)""" + return float(self.data.get("wavenumber", 0.0)) + + @property + @topic_config() + def grating(self) -> str: + """当前光栅号""" + return str(self.data.get("grating", "1")) + + @property + @topic_config() + def turret(self) -> str: + """当前光栅台号""" + return str(self.data.get("turret", "1")) + + @property + @topic_config() + def exit_port(self) -> str: + """当前出口 (0=前置, 1=侧面)""" + return str(self.data.get("exit_port", "0")) + + @property + @topic_config() + def entrance_port(self) -> str: + """当前入口 (0=前置, 1=侧面)""" + return str(self.data.get("entrance_port", "0")) + + @property + @topic_config() + def system_info(self) -> str: + """仪器系统信息""" + return str(self.data.get("system_info", "")) diff --git a/device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.yaml b/device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.yaml new file mode 100644 index 0000000..4cbfd1c --- /dev/null +++ b/device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.yaml @@ -0,0 +1,456 @@ +zolix_omni_lambda: + category: + - custom + - zolix_omni_lambda + class: + action_value_mappings: + auto-cleanup: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: cleanup参数 + type: object + type: UniLabJsonCommandAsync + auto-grating_home: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: grating_home参数 + type: object + type: UniLabJsonCommandAsync + auto-initialize: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: initialize参数 + type: object + type: UniLabJsonCommandAsync + auto-move_relative: + feedback: {} + goal: {} + goal_default: + wavelength: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + wavelength: + type: number + required: + - wavelength + type: object + result: {} + required: + - goal + title: move_relative参数 + type: object + type: UniLabJsonCommandAsync + auto-move_to: + feedback: {} + goal: {} + goal_default: + wavelength: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + wavelength: + type: number + required: + - wavelength + type: object + result: {} + required: + - goal + title: move_to参数 + type: object + type: UniLabJsonCommandAsync + auto-move_to_wavenumber: + feedback: {} + goal: {} + goal_default: + wavenumber: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + wavenumber: + type: number + required: + - wavenumber + type: object + result: {} + required: + - goal + title: move_to_wavenumber参数 + type: object + type: UniLabJsonCommandAsync + auto-post_init: + feedback: {} + goal: {} + goal_default: + ros_node: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + ros_node: + type: string + required: + - ros_node + type: object + result: {} + required: + - goal + title: post_init参数 + type: object + type: UniLabJsonCommand + auto-query_gratings: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: query_gratings参数 + type: object + type: UniLabJsonCommandAsync + auto-query_position: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: query_position参数 + type: object + type: UniLabJsonCommandAsync + auto-query_system_info: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: query_system_info参数 + type: object + type: UniLabJsonCommandAsync + auto-send_command: + feedback: {} + goal: {} + goal_default: + command: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + command: + type: string + required: + - command + type: object + result: {} + required: + - goal + title: send_command参数 + type: object + type: UniLabJsonCommandAsync + auto-set_entrance_port: + feedback: {} + goal: {} + goal_default: + port: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + port: + type: string + required: + - port + type: object + result: {} + required: + - goal + title: set_entrance_port参数 + type: object + type: UniLabJsonCommandAsync + auto-set_exit_port: + feedback: {} + goal: {} + goal_default: + port: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + port: + type: string + required: + - port + type: object + result: {} + required: + - goal + title: set_exit_port参数 + type: object + type: UniLabJsonCommandAsync + auto-set_grating: + feedback: {} + goal: {} + goal_default: + grating: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + grating: + type: string + required: + - grating + type: object + result: {} + required: + - goal + title: set_grating参数 + type: object + type: UniLabJsonCommandAsync + auto-set_port_output: + feedback: {} + goal: {} + goal_default: + value: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + value: + type: string + required: + - value + type: object + result: {} + required: + - goal + title: set_port_output参数 + type: object + type: UniLabJsonCommandAsync + auto-set_turret: + feedback: {} + goal: {} + goal_default: + turret: null + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: + turret: + type: string + required: + - turret + type: object + result: {} + required: + - goal + title: set_turret参数 + type: object + type: UniLabJsonCommandAsync + auto-stop: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: stop参数 + type: object + type: UniLabJsonCommandAsync + module: device_package_example.devices.zolix_omni_lambda.zolix_omni_lambda:ZolixOmniLambda + status_types: + entrance_port: str + exit_port: str + grating: str + status: str + system_info: str + turret: str + wavelength: float + wavenumber: float + type: python + config_info: [] + description: Zolix Omni-λ 单色仪/光谱仪 + handles: [] + icon: '' + init_param_schema: + config: + properties: + config: + type: object + device_id: + type: string + required: [] + type: object + data: + properties: + entrance_port: + type: string + exit_port: + type: string + grating: + type: string + status: + type: string + system_info: + type: string + turret: + type: string + wavelength: + type: number + wavenumber: + type: number + required: + - status + - wavelength + - wavenumber + - grating + - turret + - exit_port + - entrance_port + - system_info + type: object + version: 1.0.0 diff --git a/pyproject.toml b/pyproject.toml index 2d42496..b8e6244 100644 --- a/pyproject.toml +++ b/pyproject.toml @@ -11,6 +11,13 @@ requires-python = ">=3.10" license = {text = "MIT"} dependencies = [ "rich", + "pyserial", + "pymodbus", + "numpy", + "harvesters", + "opencv-python-headless", + "pillow", + "propar", ] [project.optional-dependencies] diff --git a/requirements.txt b/requirements.txt index 3f382dd..fc1efa9 100644 --- a/requirements.txt +++ b/requirements.txt @@ -1 +1,8 @@ rich +pyserial +pymodbus +numpy +harvesters +opencv-python-headless +pillow +propar From 70ed34a5ffa7522e665537bc3143c48e005e9ee6 Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Fri, 12 Jun 2026 13:01:28 +0800 Subject: [PATCH 05/13] =?UTF-8?q?chore:=20=E5=88=A0=E9=99=A4=E6=9C=AA?= =?UTF-8?q?=E4=BD=BF=E7=94=A8=E7=9A=84=E6=A0=B9=E7=9B=AE=E5=BD=95=E8=B0=83?= =?UTF-8?q?=E8=AF=95=E8=84=9A=E6=9C=AC?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Cursor --- jidianqi_tuigan_v2.py | 178 ------------------------------------------ test_xyz_guangdian.py | 125 ----------------------------- 2 files changed, 303 deletions(-) delete mode 100644 jidianqi_tuigan_v2.py delete mode 100644 test_xyz_guangdian.py diff --git a/jidianqi_tuigan_v2.py b/jidianqi_tuigan_v2.py deleted file mode 100644 index 6ddca6b..0000000 --- a/jidianqi_tuigan_v2.py +++ /dev/null @@ -1,178 +0,0 @@ -""" -jidianqi_tuigan.py - -RS485 Modbus relay / linear-actuator controller for CX5208W-style relay module. -This version DOES NOT use pyserial. It reuses the WinSerial object from -xyz_control_shulab.py, so it can share the same COM port with the XYZ platform. -""" - -from __future__ import annotations - -from dataclasses import dataclass -from typing import Iterable, Optional, Protocol -import time - - -class WinSerialLike(Protocol): - def reset_buffers(self) -> None: ... - def write(self, data: bytes): ... - def read(self, size: int) -> bytes: ... - - -def relay_modbus_crc(data: Iterable[int]) -> bytes: - crc = 0xFFFF - for b in data: - crc ^= b & 0xFF - for _ in range(8): - if crc & 0x0001: - crc = (crc >> 1) ^ 0xA001 - else: - crc >>= 1 - crc &= 0xFFFF - return bytes([crc & 0xFF, (crc >> 8) & 0xFF]) - - -def build_write_single_coil(slave_addr: int, coil_addr: int, on: bool) -> bytes: - payload = bytes([ - slave_addr & 0xFF, - 0x05, - (coil_addr >> 8) & 0xFF, - coil_addr & 0xFF, - 0xFF if on else 0x00, - 0x00, - ]) - return payload + relay_modbus_crc(payload) - - -def hex_bytes(data: bytes | bytearray | Iterable[int]) -> str: - return " ".join(f"{b & 0xFF:02X}" for b in data) - - -@dataclass -class RelayActuatorConfig: - slave_addr: int = 0x04 - response_wait_s: float = 0.08 - command_gap_s: float = 0.05 - strict_ack: bool = False - do1_coil: int = 0x0000 - do2_coil: int = 0x0001 - - -class RelayActuatorController: - def __init__( - self, - serial_port: WinSerialLike, - config: Optional[RelayActuatorConfig] = None, - *, - debug: bool = False, - ): - self.ser = serial_port - self.config = config or RelayActuatorConfig() - self.debug = debug - self.state = "unknown" - - def send_frame(self, frame: bytes, expected_len: int = 8) -> bytes: - self.ser.reset_buffers() - written = self.ser.write(frame) - if written is not None and int(written) != len(frame): - raise IOError(f"继电器发送不完整:{written}/{len(frame)} bytes") - - if self.debug: - print("[Relay TX]", hex_bytes(frame)) - - time.sleep(self.config.response_wait_s) - resp = self.ser.read(expected_len) - - if self.debug: - print("[Relay RX]", hex_bytes(resp) if resp else "") - - if self.config.strict_ack: - if len(resp) != expected_len: - raise TimeoutError(f"继电器响应长度不足,期望 {expected_len},实际 {len(resp)},响应={hex_bytes(resp)}") - if resp[-2:] != relay_modbus_crc(resp[:-2]): - raise ValueError(f"继电器 CRC 校验失败,响应={hex_bytes(resp)}") - if resp[:6] != frame[:6]: - raise RuntimeError(f"继电器写线圈回包异常,发送={hex_bytes(frame)},响应={hex_bytes(resp)}") - - time.sleep(self.config.command_gap_s) - return resp - - def write_coil(self, coil_addr: int, on: bool) -> bytes: - frame = build_write_single_coil(self.config.slave_addr, coil_addr, on) - return self.send_frame(frame, expected_len=8) - - def set_do1(self, on: bool) -> bytes: - return self.write_coil(self.config.do1_coil, on) - - def set_do2(self, on: bool) -> bytes: - return self.write_coil(self.config.do2_coil, on) - - def stop(self) -> None: - self.set_do1(False) - self.set_do2(False) - self.state = "stop" - - def forward(self, duration_s: float | None = None, stop_after: bool = False) -> None: - self.set_do2(False) - self.set_do1(True) - self.state = "push" - if duration_s is not None: - time.sleep(duration_s) - if stop_after: - self.stop() - - def backward(self, duration_s: float | None = None, stop_after: bool = False) -> None: - self.set_do1(False) - self.set_do2(True) - self.state = "pull" - if duration_s is not None: - time.sleep(duration_s) - if stop_after: - self.stop() - - def push(self, duration_s: float | None = None, stop_after: bool = False) -> None: - self.forward(duration_s=duration_s, stop_after=stop_after) - - def pull(self, duration_s: float | None = None, stop_after: bool = False) -> None: - self.backward(duration_s=duration_s, stop_after=stop_after) - - def go_origin_state(self) -> None: - self.pull() - - -LinearActuator485 = RelayActuatorController -LinearActuatorConfig = RelayActuatorConfig - - -def interactive_main() -> None: - from xyz_control_shulab import WinSerial, PORT, BAUDRATE - - shared_serial = WinSerial(PORT, BAUDRATE) - try: - shared_serial.open() - actuator = RelayActuatorController(shared_serial, debug=True) - print("推杆/继电器测试启动。命令:push / pull / stop / q") - actuator.go_origin_state() - while True: - cmd = input("actuator > ").strip().lower() - if cmd in {"q", "quit", "exit"}: - actuator.go_origin_state() - break - if cmd in {"push", "f", "forward"}: - actuator.push() - print("已前推。") - elif cmd in {"pull", "b", "backward"}: - actuator.pull() - print("已后退/回拉。") - elif cmd in {"stop", "s"}: - actuator.stop() - print("已停止。") - else: - print("无法识别。可用:push / pull / stop / q") - finally: - shared_serial.close() - print("串口已关闭。") - - -if __name__ == "__main__": - interactive_main() diff --git a/test_xyz_guangdian.py b/test_xyz_guangdian.py deleted file mode 100644 index 9d5bc8d..0000000 --- a/test_xyz_guangdian.py +++ /dev/null @@ -1,125 +0,0 @@ -#!/usr/bin/env python3 -""" -XYZ光电设备测试脚本 -测试串口连接和基本功能 -""" - -import asyncio -import logging -import sys -from pathlib import Path - -# 添加设备包路径 -sys.path.insert(0, str(Path(__file__).parent / "device_package_example")) - -from devices.xyz_guangdian.xyz_guangdian import XYZGuangdian - -# 配置日志 -logging.basicConfig( - level=logging.INFO, - format='%(asctime)s - %(name)s - %(levelname)s - %(message)s' -) - -async def test_xyz_device(): - """测试XYZ光电设备""" - - # 设备配置 - config = { - 'port': '/dev/tty.usbserial-BG02ANBF', # macOS串口 - 'baudrate': 9600, - 'timeout': 2.0, - 'retry_count': 3, - 'retry_delay': 0.1 - } - - print("=" * 60) - print("XYZ光电设备测试") - print("=" * 60) - print(f"串口: {config['port']}") - print(f"波特率: {config['baudrate']}") - print("-" * 60) - - # 创建设备实例 - device = XYZGuangdian( - device_id="xyz_test_001", - config=config - ) - - try: - # 1. 初始化设备 - print("\n[1/6] 初始化设备...") - success = await device.initialize() - if not success: - print("❌ 初始化失败") - print(f"状态: {device.data['status']}") - print(f"错误码: {device.data['error_code']}") - return False - print("✅ 初始化成功") - - # 2. 读取当前状态 - print("\n[2/6] 读取设备状态...") - print(f"状态: {device.data['status']}") - print(f"X轴位置: {device.data['position_x']:.2f} mm") - print(f"Y轴位置: {device.data['position_y']:.2f} mm") - print(f"Z轴位置: {device.data['position_z']:.2f} mm") - print(f"推杆状态: {device.data['push_rod_status']}") - print(f"是否使能: {device.data['is_enabled']}") - print(f"是否回零: {device.data['is_homed']}") - - # 3. 使能设备 - print("\n[3/6] 使能设备...") - success = await device.enable() - if success: - print("✅ 使能成功") - else: - print("❌ 使能失败") - - # 4. 测试获取位置 - print("\n[4/6] 获取当前位置...") - position = await device.get_position() - if position: - print(f"✅ 位置读取成功: X={position['x']:.2f}, Y={position['y']:.2f}, Z={position['z']:.2f} mm") - else: - print("❌ 位置读取失败") - - # 5. 测试推杆释放 - print("\n[5/6] 测试推杆释放...") - success = await device.release_glass() - if success: - print("✅ 推杆释放成功") - else: - print("⚠️ 推杆释放失败(可能已经是释放状态)") - - # 6. 禁用设备 - print("\n[6/6] 禁用设备...") - success = await device.disable() - if success: - print("✅ 禁用成功") - else: - print("❌ 禁用失败") - - # 清理 - print("\n[清理] 关闭连接...") - await device.cleanup() - print("✅ 清理完成") - - print("\n" + "=" * 60) - print("测试完成!") - print("=" * 60) - return True - - except Exception as e: - print(f"\n❌ 测试过程中发生错误: {e}") - import traceback - traceback.print_exc() - return False - finally: - # 确保清理 - try: - await device.cleanup() - except: - pass - -if __name__ == "__main__": - result = asyncio.run(test_xyz_device()) - sys.exit(0 if result else 1) From 38b19edea546763415696d1f31ed77fae6f5cb3e Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Fri, 12 Jun 2026 13:01:32 +0800 Subject: [PATCH 06/13] =?UTF-8?q?docs:=20=E4=B8=BA=2011=20=E4=B8=AA?= =?UTF-8?q?=E8=AE=BE=E5=A4=87=E9=A9=B1=E5=8A=A8=E6=B7=BB=E5=8A=A0=20README?= =?UTF-8?q?=20=E4=B8=8E=E4=BA=A7=E5=93=81=E8=B5=84=E6=96=99?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Cursor --- .../devices/bronkhorst_el_flow/README.md | 72 ++++++++++++++++ .../devices/chi760e/README.md | 78 ++++++++++++++++++ .../devices/cmos_detector/README.md | 76 +++++++++++++++++ .../devices/cni_laser_msl_u_532/README.md | 76 +++++++++++++++++ .../devices/daheng_gci060505/README.md | 63 ++++++++++++++ .../devices/dhjf_circulation_bath/README.md | 82 +++++++++++++++++++ .../devices/longer_bt100/README.md | 72 ++++++++++++++++ .../devices/runze_sy03b_t08/README.md | 73 +++++++++++++++++ .../devices/solenoid_valve_4v110/README.md | 78 ++++++++++++++++++ .../devices/xyz_guangdian/README.md | 67 +++++++++++++++ .../devices/zolix_omni_lambda/README.md | 79 ++++++++++++++++++ 11 files changed, 816 insertions(+) create mode 100644 device_package_example/devices/bronkhorst_el_flow/README.md create mode 100644 device_package_example/devices/chi760e/README.md create mode 100644 device_package_example/devices/cmos_detector/README.md create mode 100644 device_package_example/devices/cni_laser_msl_u_532/README.md create mode 100644 device_package_example/devices/daheng_gci060505/README.md create mode 100644 device_package_example/devices/dhjf_circulation_bath/README.md create mode 100644 device_package_example/devices/longer_bt100/README.md create mode 100644 device_package_example/devices/runze_sy03b_t08/README.md create mode 100644 device_package_example/devices/solenoid_valve_4v110/README.md create mode 100644 device_package_example/devices/xyz_guangdian/README.md create mode 100644 device_package_example/devices/zolix_omni_lambda/README.md diff --git a/device_package_example/devices/bronkhorst_el_flow/README.md b/device_package_example/devices/bronkhorst_el_flow/README.md new file mode 100644 index 0000000..5effb70 --- /dev/null +++ b/device_package_example/devices/bronkhorst_el_flow/README.md @@ -0,0 +1,72 @@ +# Bronkhorst MFC + +## 简介 + +Bronkhorst EL-FLOW Prestige 质量流量控制器(MFC)驱动,支持读取流量/温度、设置设定值与用户标签。 + +## 设备 ID + +`bronkhorst_el_flow` + +## 通信方式 + +- 协议:RS232/RS485(`propar` 库) +- 默认:38400 baud,从站地址 3 + +## 依赖 + +- `propar` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM12` | 串口号 | +| `baudrate` | `38400` | 波特率 | +| `address` | `3` | 设备地址 | +| `channel` | `1` | 通道号 | +| `threshold` | `2.0` | 流量偏差阈值(%) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与释放 +- `read_value`:读取流量、设定值、温度 +- `set_setpoint` / `set_setpoint_percent` / `stop`:流量控制 +- `set_threshold` / `set_user_tag`:参数设置 + +## 状态属性 + +`status`、`flow`、`setpoint`、`temperature`、`valve_output`、`capacity_unit`、`user_tag`、`level`、`rssi`、`value` + +## Graph 示例 + +`graph_example_bronkhorst_el_flow.json` + +## 启动验证 + +```bash +unilab --check_mode --devices ./device_package_example --external_devices_only +unilab --devices ./device_package_example --external_devices_only \ + -g device_package_example/devices/bronkhorst_el_flow/graph_example_bronkhorst_el_flow.json +``` + +## 产品资料 + +### 产品简介 + +Bronkhorst EL-FLOW Prestige 是面向实验室与工业应用的高端气体质量流量控制器/流量计(MFC/MFM),内置 100 种气体数据库,支持实时温压补偿,精度与长期稳定性较高。 + +### 产品特点 + +- 量程约 0.014 mlₙ/min ~ 100 ln/min(视具体型号) +- 精度:±0.5% Rd + ±0.1% FS(标准) +- 工作压力最高 100 bar;工作温度 -10 ~ +70 ℃ +- 通信:RS232 标准,可选 Modbus/PROFIBUS/EtherCAT 等 +- 防护等级 IP40 + +### 资料链接 + +- [Bronkhorst 官方产品页](https://www.bronkhorst.com/products/gas-flow/el-flow-prestige/) +- [EL-FLOW Prestige 数据手册 PDF](https://pdf.directindustry.com/pdf/bronkhorst/el-flow-prestige-mass-flow-meters-controllers-gas/15524-624442.html) + +> 说明:本驱动通过 `propar` 库经 RS232 通信,请确认现场仪表接口与地址配置。 diff --git a/device_package_example/devices/chi760e/README.md b/device_package_example/devices/chi760e/README.md new file mode 100644 index 0000000..98fe727 --- /dev/null +++ b/device_package_example/devices/chi760e/README.md @@ -0,0 +1,78 @@ +# CHI760E 电化学工作站 + +## 简介 + +辰华 CHI760E 电化学工作站驱动,通过 CHI 软件宏命令(`.mcr`)控制,支持 CV / LSV / CA / OCP / NPV / EIS 等实验。 + +## 设备 ID + +`chi760e` + +## 通信方式 + +- 方式:本地 subprocess 调用 `chi760e.exe /runmacro` +- 平台:**仅 Windows** + +## 依赖 + +- `numpy`(可选,用于解析数据文件) + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `chi_exe_path` | — | CHI 软件可执行文件路径(必填) | +| `data_folder` | — | 实验数据与宏文件目录(必填) | +| `default_sens` | `1e-6` | 默认灵敏度 (A/V) | + +## 主要动作 + +- `initialize` / `cleanup`:验证路径与目录 +- `run_cv` / `run_lsv` / `run_ca` / `run_ocp` / `run_npv` / `run_eis`:电化学实验 +- `stop_operation`:强制结束 CHI 进程 +- `list_data_files` / `read_data`:数据文件管理 + +## 状态属性 + +`status`、`technique`、`last_data_file`、`last_experiment_time`、`data_folder` + +## Graph 示例 + +`graph_example_chi760e.json` + +## 注意事项 + +- 需在 Windows 上安装 CHI760E 软件 +- 实验为阻塞式 subprocess,单次实验可能耗时较长 + +## 产品资料 + +### 产品简介 + +上海辰华 CHI760E 是通用**双恒电位仪**电化学工作站,可同时控制同一电解池中的两个工作电极,典型应用为旋转环盘电极(RRDE),集成 CV、LSV、CA、OCP、NPV、EIS 等多种电化学技术。 + +### 主要特点 + +- 双通道同步扫描/采样,最高扫速 10,000 V/s +- 16 位数据采集,双通道同步采样最高 1 MHz +- 交流阻抗范围 0.00001 Hz ~ 1 MHz +- 超微电极稳态电流测量(电流下限 < 50 pA) + +### 技术参数(参考) + +| 项目 | 参数 | +|---|---| +| 电位范围 | ±10 V | +| 最大电流 | ±250 mA(双通道合计),峰值 ±350 mA | +| 槽压 | ±13 V | +| 电流测量 | ±10 pA ~ ±0.25 A(12 量程) | +| CV/LSV 扫速 | 1×10⁻⁶ ~ 10,000 V/s | +| EIS 频率 | 0.00001 ~ 1 MHz | +| 生产厂家 | 上海辰华仪器有限公司 | + +### 资料链接 + +- [北京化工大学设备介绍](https://nhca3.buct.edu.cn/2021/0126/c1365a144584/page.htm) +- [鑫视科 CHI760E 产品页](https://www.shinsco.cn/products/2101/) + +> 说明:驱动通过 Windows 下 CHI 软件宏命令(`.mcr`)控制,需安装 `chi760e.exe`。 diff --git a/device_package_example/devices/cmos_detector/README.md b/device_package_example/devices/cmos_detector/README.md new file mode 100644 index 0000000..f05cd7d --- /dev/null +++ b/device_package_example/devices/cmos_detector/README.md @@ -0,0 +1,76 @@ +# CMOS 线阵检测器 + +## 简介 + +LCAMV8 CMOS 线阵检测器(S11639-01,2048 像素)驱动,支持积分时间、增益、单帧/连续采集及波长矫正。 + +## 设备 ID + +`cmos_detector` + +## 通信方式 + +- 协议:USB 虚拟串口 ASCII 帧 +- 默认:115200 baud,8N1 + +## 依赖 + +- `pyserial` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM10` | 串口号 | +| `baudrate` | `115200` | 波特率 | +| `save_dir` | `./cmos_data` | CSV 数据保存目录 | + +## 主要动作 + +- `initialize` / `cleanup`:打开/关闭串口 +- `start_single_acquisition` / `start_continuous_acquisition` / `stop_acquisition` / `read_frame`:采集控制 +- `set_integration_time` / `set_gain` / `set_offset` 等:参数设置 +- `read_correction_coefficients` / `save_data_to_file`:波长映射与数据导出 + +## 状态属性 + +`status`、`level`、`value`(JSON 像素数组)、`integration_time`、`gain`、`version_info` 等 + +## Graph 示例 + +`graph_example_cmos_detector.json` + +## 注意事项 + +- 单次采集(0x01)无响应,驱动使用连续采集 + 停止实现单帧 +- 布尔状态以字符串 `"true"` / `"false"` 表示 + +## 产品资料 + +### 产品简介 + +LCAMV8-S11639 线阵检测器模组基于滨松(Hamamatsu)**S11639-01** CMOS 线阵传感器,集成 ARM+FPGA 驱动板,通过 USB 虚拟串口通信,适用于光谱分析、紫外/近红外检测等场景。 + +### 传感器核心参数(S11639-01) + +| 项目 | 参数 | +|---|---| +| 像素数 | 2048 × 1 | +| 像元尺寸 | 14 × 200 μm | +| 有效感光长度 | 28.672 mm | +| 光谱响应 | 200 ~ 1000 nm | +| 灵敏度 | 1300 V/(lx·s) | +| 行速率(最大) | 4672 lines/s | +| 供电 | 5 V 单电源 | + +### 模组特点(LCAMV8 系列) + +- 接口:USB Type-C、TTL,支持外触发 +- 最高帧率可达 200 fps 以上(视配置) +- 16 bit 专业 CCD 处理器 + +### 资料链接 + +- [Hamamatsu S11639-01 官方页](https://www.hamamatsu.com/eu/en/product/optical-sensors/image-sensor/ccd-cmos-nmos-image-sensor/line-sensor/for-spectrophotometry/S11639-01.html) +- [S11639-01 数据手册 PDF](https://www.hamamatsu.com/content/dam/hamamatsu-photonics/sites/documents/99_SALES_LIBRARY/ssd/s11639-01_kmpd1163e.pdf) +- [依迈光电 LCAMV8 模组介绍](http://www.imaioptics.com/index.php?a=index&aid=55&c=view&m=home) diff --git a/device_package_example/devices/cni_laser_msl_u_532/README.md b/device_package_example/devices/cni_laser_msl_u_532/README.md new file mode 100644 index 0000000..e79eef5 --- /dev/null +++ b/device_package_example/devices/cni_laser_msl_u_532/README.md @@ -0,0 +1,76 @@ +# CNI 532nm 激光器 + +## 简介 + +CNI MSL-U-532-50mW 激光器驱动,通过 Arduino Nano + MCP4725 DAC 控制功率,串口发送 `SET 0-100` 指令。 + +## 设备 ID + +`cni_laser_msl_u_532` + +## 通信方式 + +- 协议:Arduino 串口 ASCII(9600 baud) +- 固件标识:`ArduinoUno_LaserValve` + +## 依赖 + +- `pyserial` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM13` | 串口号 | +| `baudrate` | `9600` | 波特率 | +| `timeout` | `2.0` | 通信超时 (s) | +| `max_power_mw` | `50.0` | 最大功率 (mW) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与释放 +- `turn_on` / `turn_off`:开关激光 +- `set_power` / `set_power_percentage`:功率设置 +- `emergency_stop`:紧急关断(DAC 置 0) + +## 状态属性 + +`status`、`laser_on`、`power`、`power_percentage`、`wavelength` + +## Graph 示例 + +`graph_example_cni_laser_msl_u_532.json` + +## 注意事项 + +- 上电后需等待 Arduino 复位(约 2.5 s) +- 激光器使用前请确认光路安全 + +## 产品资料 + +### 产品简介 + +长春新产业(CNI)**MSL-U-532** 是超紧凑单纵模 532 nm 连续绿光激光器,TEM00 模式,适用于拉曼光谱、DNA 测序、全息/干涉测量等。 + +### 技术参数(MSL-U-532,参考) + +| 项目 | 参数 | +|---|---| +| 波长 | 532 ± 1 nm | +| 工作模式 | CW 连续 | +| 输出功率 | 1 ~ 1000 mW(视订购配置,本驱动默认 50 mW) | +| 线宽 | < 0.00001 nm | +| 相干长度 | > 50 m | +| M² | < 1.2 | +| 横模 | TEM00 | +| 功率稳定性 | < 1~5%(4 h,RMS) | +| 振幅噪声 | < 0.5%(1 Hz~20 MHz) | +| 工作温度 | 10 ~ 40 ℃ | +| 预期寿命 | ~10000 h | + +### 资料链接 + +- [CNI 532 nm 单纵模激光系列](https://www.cnilaser.com/single_frequency_laser532.htm) +- [MSL-U-532 规格(Oceanhood)](https://en.oceanhoodtw.com/products_detail/1046) + +> 说明:本实验室通过 Arduino + MCP4725 DAC 经串口 `SET 0-100` 控制功率,非原厂标准 RS232 协议。 diff --git a/device_package_example/devices/daheng_gci060505/README.md b/device_package_example/devices/daheng_gci060505/README.md new file mode 100644 index 0000000..d57bcbb --- /dev/null +++ b/device_package_example/devices/daheng_gci060505/README.md @@ -0,0 +1,63 @@ +# GCI-060505 LED 光源 + +## 简介 + +大恒 GCI-060505 LED 光源驱动,通过 Arduino + MCP4725 DAC 控制亮度,支持 PING/ON/OFF/BRIGHT/STATUS 指令。 + +## 设备 ID + +`daheng_gci060505` + +## 通信方式 + +- 协议:Arduino 串口 ASCII +- 默认:115200 baud + +## 依赖 + +- `pyserial` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM14` | 串口号 | +| `baudrate` | `115200` | 波特率 | +| `timeout` | `2` | 读超时 (s) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与释放 +- `turn_on` / `turn_off`:开关光源 +- `set_brightness`:设置亮度 0–100% +- `refresh_status`:从 Arduino 读取当前状态 + +## 状态属性 + +`status`、`brightness`、`light_on`、`max_brightness` + +## Graph 示例 + +`graph_example_daheng_gci060505.json` + +## 注意事项 + +- 打开串口后 Arduino 会 DTR 复位,需等待约 2 s + +## 产品资料 + +### 产品简介 + +大恒光电 **GCI** 系列为光学仪器配件产品线。本实验室 **GCI-060505** 为 LED 光源模组,经 **Arduino + MCP4725 DAC** 二次开发,通过串口 ASCII 指令控制开关与亮度(0–100%)。 + +### 集成方案特点 + +- 通信:115200 baud 串口(PING / ON / OFF / BRIGHT / STATUS) +- 亮度:0–100% PWM/DAC 模拟调光 +- 适用于显微照明、相机校正等场景 + +### 资料链接 + +- [大恒光电官网](https://www.golight.com.cn/)(GCI 系列产品) + +> 说明:未找到 GCI-060505 公开详细规格书;光源 LED 电气参数取决于具体灯珠与驱动电路,请以实验室 BOM 为准。 diff --git a/device_package_example/devices/dhjf_circulation_bath/README.md b/device_package_example/devices/dhjf_circulation_bath/README.md new file mode 100644 index 0000000..ae7885e --- /dev/null +++ b/device_package_example/devices/dhjf_circulation_bath/README.md @@ -0,0 +1,82 @@ +# DHJF 循环水浴 + +## 简介 + +DHJF-2005A 低温恒温搅拌反应浴驱动,Modbus RTU 通信,支持温度设定、搅拌控制与多段程序。 + +## 设备 ID + +`dhjf_circulation_bath` + +## 通信方式 + +- 协议:Modbus RTU(RS485) +- 默认:9600 baud,8N1,从站 ID 1 + +## 依赖 + +- `pymodbus` +- `pyserial` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM4` | 串口号 | +| `slave_id` | `1` | Modbus 从站地址 | +| `baudrate` | `9600` | 波特率 | +| `timeout` | `1.0` | 通信超时 (s) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与释放 +- 温度/搅拌设定、程序段控制(见驱动与 YAML) + +## 状态属性 + +`status`、`temp`、`temp_target`、`stir_speed`、`temp_warning` 等 + +## Graph 示例 + +`graph_dhjf_circulation_bath.json` + +## 注意事项 + +- 温度寄存器为 ×100 整型写入 +- 兼容 pymodbus 2.x / 3.x + +## 产品资料 + +### 产品简介 + +DHJF-2005A 低温恒温搅拌反应浴(郑州长城科工贸)向外部提供恒温冷源或作为恒温槽使用,适用于化学、生物、物理检测等实验室,可冷却/加热烧瓶、试管等反应容器,也可为其他设备提供冷热源。 + +### 产品特点 + +- 温度控制采用 PID,控温精度高;内置磁力搅拌,转速 100–1000 rpm +- 全封闭风冷进口压缩机,304 不锈钢储液槽 +- RS485 接口,遵循 Modbus RTU 协议(与本驱动一致) +- 支持多段程序温度控制 + +### 技术参数(DHJF-2005A,参考) + +| 项目 | 参数 | +|---|---| +| 型号 | DHJF-2005A | +| 温度范围 | -20 ~ 99 ℃ | +| 温度稳定性 | ±0.2 ℃ | +| 显示精度 | 0.01 ℃ | +| 储液槽容积 | 5 L | +| 储液槽尺寸 | Φ250×130 mm | +| 开口尺寸 | Φ210 mm | +| 加热功率 | 1500 W | +| 整机功率 | 2210 W | +| 制冷剂 | R404A | +| 电源 | 220 V~,50 Hz | +| 外形尺寸 | 385×560×735 mm(W×D×H) | +| 生产厂家 | 郑州长城科工贸有限公司 | + +### 资料链接 + +- [仪器网:DHJF-2005A 产品页](https://www.yiqi.com/product/detail_13619818.html) +- [长城科工贸:DHJF-2005 系列参数表](http://www.zzgwsit.com.cn/products/dwhwjb2005.html) diff --git a/device_package_example/devices/longer_bt100/README.md b/device_package_example/devices/longer_bt100/README.md new file mode 100644 index 0000000..c8d53b8 --- /dev/null +++ b/device_package_example/devices/longer_bt100/README.md @@ -0,0 +1,72 @@ +# 兰格蠕动泵 + +## 简介 + +兰格 BT100-2J 蠕动泵驱动,WJ/RJ ASCII 协议,RS485 通信,支持转速、方向与启停控制。 + +## 设备 ID + +`longer_bt100` + +## 通信方式 + +- 协议:RS485 自定义帧(flag E9 + 地址 + PDU + FCS) +- 默认:1200 baud,8N1E(偶校验) + +## 依赖 + +- `pyserial` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM4` | 串口号 | +| `baudrate` | `1200` | 波特率 | +| `address` | `1` | 设备地址 | +| `serial_timeout` | `0.5` | 读超时 (s) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与释放 +- `start_pump` / `stop_pump`:启停 +- `set_speed` / `set_direction`:转速与方向 + +## 状态属性 + +`status`、`speed`、`direction`、`is_fullspeed` + +## Graph 示例 + +`graph_longer_bt100.json` + +## 注意事项 + +- 1200 baud 下帧传输较慢,建议 `serial_timeout` ≥ 0.5 s +- 字节填充规则:E8→E8 00,E9→E8 01 + +## 产品资料 + +### 产品简介 + +保定兰格 **BT100-2J** 是实验室常用精密蠕动泵,支持 RS485 通信及外控启停/调速,流量范围宽,可配多种泵头(YZ1515x、DG 系列等)。 + +### 技术参数 + +| 项目 | 参数 | +|---|---| +| 转速范围 | 0.1 ~ 100 rpm(正反转) | +| 流量范围 | 0.0002 ~ 380 ml/min(单管,视泵头/管径) | +| 转速分辨率 | 0.1 rpm | +| 通信 | RS485(本驱动 1200 baud WJ/RJ 协议) | +| 外控 | 启停、方向、0–5V/4–20mA/0–10kHz 调速 | +| 电源 | AC 90–260 V / 30 W | +| 防护等级 | IP31 | +| 外形尺寸 | 232 × 142 × 149 mm | +| 重量 | 2.3 kg | +| 生产厂家 | 保定兰格恒流泵有限公司 | + +### 资料链接 + +- [兰格 BT100-2J 官方产品页](http://shop.longerpump.com.cn/ProductShow_6824.html) +- [BT100-2J 使用说明书](https://rudongbeng.com/article-68.html) diff --git a/device_package_example/devices/runze_sy03b_t08/README.md b/device_package_example/devices/runze_sy03b_t08/README.md new file mode 100644 index 0000000..9376d8d --- /dev/null +++ b/device_package_example/devices/runze_sy03b_t08/README.md @@ -0,0 +1,73 @@ +# 润泽注射泵 + +## 简介 + +润泽 SY-03B 陶瓷注射泵(T-08 八通分配阀)驱动,ASCII DT 格式 RS232/RS485 通信,25 mL 注射器。 + +## 设备 ID + +`runze_sy03b_t08` + +## 通信方式 + +- 协议:ASCII DT 格式 +- 默认:9600 baud + +## 依赖 + +- `pyserial` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM4` | 串口号 | +| `baudrate` | `9600` | 波特率 | +| `address` | `0` | 设备地址开关值 (0–15) | +| `syringe_volume` | `25.0` | 注射器体积 (mL) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与释放 +- 吸液、分液、阀位切换、复位等(见驱动与 YAML) + +## 状态属性 + +`status`、`mode`、`position`、`valve_port` 等 + +## Graph 示例 + +`graph_runze_sy03b_t08.json` + +## 注意事项 + +- 全行程约 6000 步(25 mL) +- T-08 阀为 8 口分配阀,C 口连通 1–8 + +## 产品资料 + +### 产品简介 + +南京润泽 **SY-03B** 是高精度工业陶瓷注射泵,本配置配 **T-08 八通分配阀**(C 口可选择连通 1–8 号端口)。采用 ASCII DT 协议经 RS485 控制,标准注射器 25 mL(6000 步全行程)。 + +### 技术参数 + +| 项目 | 参数 | +|---|---| +| 型号 | ZSB-SY03B-T08 | +| 额定行程 | 60 mm(6000 步标准 / 48000 步微步) | +| 液量准确度 | ≤ 1%(额定行程) | +| 重复性 | 0.3 ~ 0.5% | +| 线速度 | 0.01 ~ 60 mm/s | +| 适配注射器 | 25 μl ~ 25 ml | +| 通信 | RS232/RS485,9600~115200 bps | +| 协议 | ASCII DT / Modbus(视固件) | +| 电源 | DC 24 V / 3 A | +| 重量 | 约 2.2 kg | +| 生产厂家 | 南京润泽流体控制设备有限公司 | + +### 资料链接 + +- [SY-03B 产品页(中文)](https://www.runzefluidsystem.com/list_19/1904.html) +- [SY-03B 英文手册 PDF](https://www.runzefluid.com/uploads/file/sy-03b-syringe-pump.pdf) +- [SY-03 V2.4 协议说明 PDF](https://www.runzefluid.com/uploads/file/sy-03-v2-1.pdf) diff --git a/device_package_example/devices/solenoid_valve_4v110/README.md b/device_package_example/devices/solenoid_valve_4v110/README.md new file mode 100644 index 0000000..d9f76fa --- /dev/null +++ b/device_package_example/devices/solenoid_valve_4v110/README.md @@ -0,0 +1,78 @@ +# 4V110 电磁阀 + +## 简介 + +亚德客 4V110-06 DC24V 二位五通电磁阀驱动,通过 Arduino Uno GPIO + 继电器模块控制 24 V 线圈。 + +## 设备 ID + +`solenoid_valve_4v110` + +## 通信方式 + +- 协议:Arduino 串口 ASCII +- 指令:`VALVE ON` / `VALVE OFF` / `VALVE?` +- 默认:9600 baud + +## 依赖 + +- `pyserial` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM3` | 串口号 | +| `baudrate` | `9600` | 波特率 | +| `timeout` | `1` | 读超时 (s) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与释放(初始化时关闭阀门) +- `open` / `close`:开/关电磁阀 +- `set_valve_position`:设置 `"Open"` / `"Closed"` +- `is_open` / `is_closed`:查询状态 +- `send_command`:发送自定义指令 + +## 状态属性 + +`status`、`valve_position` + +## Graph 示例 + +`graph_example_solenoid_valve_4v110.json` + +## 注意事项 + +- 可与 CNI 激光器共用同一 Arduino 固件(不同指令集) +- 未知位置参数时默认关闭(安全策略) + +## 产品资料 + +### 产品简介 + +亚德客(Airtac)**4V110-06** 是五口二位单电控电磁阀,进气/出气口径 PT1/8(G1/8),用于控制气缸或流体换向。本实验室通过 Arduino 继电器模块经 24 V 线圈驱动。 + +### 技术参数 + +| 项目 | 参数 | +|---|---| +| 型号 | 4V110-06 | +| 型式 | 五口二位,内先导 | +| 接管口径 | PT1/8(G1/8) | +| 有效截面积 | 10 ~ 12 mm²(Cv ≈ 0.56–0.67) | +| 使用压力 | 0.15 ~ 0.8 MPa | +| 耐压 | 1.2 MPa | +| 工作介质 | 经 40 μm 过滤的压缩空气 | +| 工作温度 | -20 ~ 70 ℃ / 5 ~ 50 ℃ | +| 线圈功耗 | 2.5 ~ 3 W(DC 24 V 常见) | +| 防护等级 | IP65 | +| 重量 | 约 120 g | +| 品牌 | 亚德客 Airtac | + +### 资料链接 + +- [亚德客 4V110-06 参数(代理商)](http://www.herionimi.com/Products-36341907.html) +- [AirTAC 4V110-06 规格表](https://mech-mall.com/product/4v110-06-solenoid-valve) + +> 说明:本驱动经 Arduino 串口发送 `VALVE ON/OFF`,非直接驱动电磁阀线圈。 diff --git a/device_package_example/devices/xyz_guangdian/README.md b/device_package_example/devices/xyz_guangdian/README.md new file mode 100644 index 0000000..5d7a422 --- /dev/null +++ b/device_package_example/devices/xyz_guangdian/README.md @@ -0,0 +1,67 @@ +# XYZ 三维平台 + +## 简介 + +XYZ 光电工作台驱动,控制三轴运动平台与推杆装置,Modbus RTU 通信,支持绝对/相对移动与推杆夹紧/释放。 + +## 设备 ID + +`xyz_guangdian` + +## 通信方式 + +- 协议:Modbus RTU(RS485) +- 默认:9600 baud +- 从站:X=0x01,Y=0x02,Z=0x03,推杆=0x04 + +## 依赖 + +- `pyserial`(或 pymodbus,见驱动实现) + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM35` | 串口号 | +| `baudrate` | `9600` | 波特率 | +| `timeout` | `2.0` | 通信超时 (s) | +| `retry_count` | `3` | 重试次数 | +| `retry_delay` | `0.1` | 重试间隔 (s) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与释放 +- 三轴移动、回零、推杆夹紧/释放/停止(见驱动与 YAML) + +## 状态属性 + +`status`、`x_position`、`y_position`、`z_position`、`push_rod_status`、`error_code` 等 + +## Graph 示例 + +`graph_example_xyz_guangdian.json` + +## 注意事项 + +- 推杆控制已内嵌在驱动中,无需额外脚本 +- 多轴共用同一 RS485 总线时注意从站地址 + +## 产品资料 + +### 产品简介 + +**XYZ 光电工作台**为本实验室定制三轴运动平台 + 推杆系统,采用 Modbus RTU(RS485)控制。X/Y/Z 三轴步进电机与推杆装置共用总线,从站地址分别为 0x01、0x02、0x03、0x04。 + +### 系统组成 + +| 从站 | 地址 | 功能 | +|---|---|---| +| X 轴 | 0x01 | 水平运动 | +| Y 轴 | 0x02 | 进给运动 | +| Z 轴 | 0x03 | 升降运动 | +| 推杆 | 0x04 | 夹紧/释放 | + +### 说明 + +- 无公开商用型号与说明书;参数与限位以实验室机械设计为准 +- 推杆控制已内嵌于 `xyz_guangdian` 驱动,无需额外脚本 diff --git a/device_package_example/devices/zolix_omni_lambda/README.md b/device_package_example/devices/zolix_omni_lambda/README.md new file mode 100644 index 0000000..c7645dd --- /dev/null +++ b/device_package_example/devices/zolix_omni_lambda/README.md @@ -0,0 +1,79 @@ +# Zolix Omni-λ + +## 简介 + +Zolix Omni-λ 单色仪/光谱仪驱动,串口 ASCII 指令控制波长/波数移动、光栅切换与出入口选择。 + +## 设备 ID + +`zolix_omni_lambda` + +## 通信方式 + +- 协议:Serial ASCII,`\r` 结束符 +- 默认:19200 baud,8N1 +- 响应以 `OK` 或 `Exx` 结尾 + +## 依赖 + +- `pyserial` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM11` | 串口号 | +| `baudrate` | `19200` | 波特率 | +| `timeout` | `5` | 通信超时 (s) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与释放 +- `move_to` / `move_relative` / `move_to_wavenumber`:波长/波数移动 +- `set_grating` / `grating_home` / `set_turret`:光栅控制 +- `set_exit_port` / `set_entrance_port`:光路切换 +- `stop` / `query_position` / `send_command`:控制与查询 + +## 状态属性 + +`status`、`wavelength`、`wavenumber`、`grating`、`turret`、`exit_port`、`entrance_port`、`system_info` + +## Graph 示例 + +`graph_example_zolix_omni_lambda.json` + +## 注意事项 + +- 移动类动作为阻塞式,需等待设备返回 Idle +- 动作参数类型仅支持 `float` / `str`(框架限制) + +## 产品资料 + +### 产品简介 + +卓立汉光(Zolix)**Omni-λ** 系列是影像校正光栅单色仪/光谱仪,C-T 光路结构,支持计算机控制波长扫描、光栅切换与出入口选择,广泛用于荧光、拉曼、吸收光谱等。 + +### 产品特点 + +- 焦距可选 200 / 320 / 500 / 750 mm +- 杂散光抑制比约 1×10⁻⁵ +- 狭缝 0.01–3 mm 手动可调(可选自动狭缝) +- 通信:USB 2.0 标准,可选 RS-232;本驱动使用 **RS232 ASCII 协议** + +### 技术参数(Omni-λ300i 系列参考) + +| 项目 | 参数 | +|---|---| +| 焦距 | 320 mm | +| 相对孔径 | F/4.2 | +| 光栅 | 68×68 mm,三光栅台 | +| 波长准确度 | ±0.2 nm(@1200 g/mm) | +| 扫描步距 | 0.005 nm | +| 杂散光 | 1×10⁻⁵ | +| 生产厂家 | 北京卓立汉光仪器有限公司 | + +### 资料链接 + +- [Omni-λ 系列概览](https://zolix.com.cn/Product_desc/1324_353.html) +- [Omni-λ300i 规格](https://www.zolix.com.cn/Product_desc/1199_1564.html) +- [Omni-λ750i 规格](https://www.zolix.com.cn/Product_desc/1324_1566.html) From 9a3c31427e2a264e0e3037a5a2312b82a8dd8877 Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Fri, 12 Jun 2026 13:01:35 +0800 Subject: [PATCH 07/13] =?UTF-8?q?fix(hk=5Fa0):=20=E6=8C=89=E5=8D=8E?= =?UTF-8?q?=E6=8E=A7=20RS485=20=E6=A8=A1=E6=8B=9F=E9=87=8F=E8=BE=93?= =?UTF-8?q?=E5=87=BA=E6=89=8B=E5=86=8C=E5=AF=B9=E9=BD=90=E5=AF=84=E5=AD=98?= =?UTF-8?q?=E5=99=A8=E4=B8=8E=20API?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Cursor --- .../devices/hk_a0/README.md | 136 +++++++++++++++++ device_package_example/devices/hk_a0/hk_a0.py | 142 ++++++++++-------- .../devices/hk_a0/hk_a0.yaml | 23 ++- 3 files changed, 234 insertions(+), 67 deletions(-) create mode 100644 device_package_example/devices/hk_a0/README.md diff --git a/device_package_example/devices/hk_a0/README.md b/device_package_example/devices/hk_a0/README.md new file mode 100644 index 0000000..e773e80 --- /dev/null +++ b/device_package_example/devices/hk_a0/README.md @@ -0,0 +1,136 @@ +# 华控模拟量输出 + +## 简介 + +华控电子(惠州)**模拟量输出**模块驱动,RS485 Modbus RTU,通过功能码 **06/10** 写保持寄存器设定各通道电压/电流输出。 + +## 设备 ID + +`hk_a0` + +## 通信方式 + +- 协议:Modbus RTU(RS485) +- 默认:9600 baud,8N1,从站地址 1 + +## 依赖 + +- `pymodbus` +- `pyserial` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `/dev/ttyUSB0` | 串口号 | +| `baudrate` | `9600` | 波特率 | +| `slave_address` | `1` | Modbus 从站地址 | +| `channel_count` | `6` | 输出路数(手册支持 1~12 路) | +| `output_max` | `5.0` | 单通道上限 (V),0~10V 模块设为 `10.0` | +| `timeout` | `1.0` | 通信超时 (s) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与释放 +- `set_output`:设置单通道输出 +- `stop_all`:全部通道置 0 +- `read_outputs`:读取各通道当前设定值(FC03) + +## 状态属性 + +`status`、`outputs` + +## Graph 示例 + +`graph_hk_a0.json` + +## 注意事项 + +- 输出寄存器采用**固定 3 位小数**:`1.000 V → 1000` +- 第 1 路寄存器地址 **0x000A**,第 n 路为 `0x000A + (n-1)` +- 修改站号/波特率/校验需写配置寄存器并**重新上电**后生效 + +## 本实验室配置说明 + +驱动默认参数适用于常见 **6 路、0~5 V** 电压输出模块;若现场模块规格不同,请在 **graph / config** 中修改,无需改驱动代码。 + +| 现场情况 | 建议 config | +|---|---| +| 6 路 0~5 V(默认) | `channel_count: 6`,`output_max: 5.0` | +| 4 / 8 / 12 路 | 将 `channel_count` 改为实际路数(1~12) | +| 0~10 V 模块 | `output_max: 10.0` | +| 电流输出模块 | 寄存器缩放规则相同(固定 3 位小数);`set_output` 传入的物理量单位与模块一致(µA 或 A,见模块丝印/订货型号) | +| 非默认串口/站号 | 修改 `port`、`slave_address`、`baudrate` | + +Graph 示例片段(`graph_hk_a0.json`): + +```json +"config": { + "port": "COM3", + "slave_address": 1, + "baudrate": 9600, + "channel_count": 6, + "output_max": 5.0 +} +``` + +> 设备 ID `hk_a0` 为 Uni-Lab 注册名;硬件为华控 RS485 模拟量**输出**模块,与模拟量**输入**模块协议不同,勿混用手册。 + +## 产品资料 + +### 产品简介 + +华控电子(惠州)有限公司模拟量输出系列,支持 **1~12 路**输出,量程可选: + +- 电压:0~5 V DC / 0~10 V DC +- 电流:0~20 mA / 4~20 mA + +12 位分辨率(电压 1 mV、电流 1 µA 级),RS485 Modbus RTU,地址 1~255、波特率可设且掉电保存。 + +### 产品参数(手册 §1.3) + +| 项目 | 参数 | +|---|---| +| 供电 | 6~30 V DC,约 0.1 A | +| 通讯 | RS485(隔离/非隔离可选) | +| 输出路数 | 1~12 路 | +| 分辨率 | 12 位 | +| 精度 | ±1‰ | +| 协议 | Modbus RTU(03/06/10) | +| 波特率 | 9600 / 14400 / 19200 / 38400 / 56000 / 57600 / 115200 | +| 工作温度 | -40 ~ +85 ℃ | +| 生产厂家 | 华控电子(惠州)有限公司 | + +### 保持寄存器定义(手册 §2.2) + +| 协议地址 | PLC 地址 | 功能 | +|---|---|---| +| 000AH | 40011 | 第 1 路输出设定(固定 3 位小数,1 V = 1000) | +| 000BH | 40012 | 第 2 路 | +| … | … | … | +| 0015H | 40022 | 第 12 路 | +| 0032H | 40051 | RS485 站号(1~255,掉电保存,改后重新上电) | +| 0033H | 40052 | 波特率(0=4800 … 7=115200,掉电保存) | +| 003DH | 40062 | 校验(0 无 / 1 奇 / 2 偶,掉电保存) | + +### 指令示例(手册 §2.2) + +**第 1 路输出 1.000 V(FC06,写 000AH = 1000)** + +- 请求:`01 06 00 0A 03 E8 …`(1000 = 0x03E8) + +**读第 1 路设定值(FC03)** + +- 请求:`01 03 00 0A 00 01 …` + +**改站号为 2(FC06,写 0032H)** + +- `01 06 00 32 00 02 A9 C4` + +**改波特率为 38400(FC06,写 0033H,值 4)** + +- `01 06 00 33 00 04 78 06` + +### 资料 + +- 手册:《模拟量输出系列使用手册(RS485版) V2.0》(华控电子) diff --git a/device_package_example/devices/hk_a0/hk_a0.py b/device_package_example/devices/hk_a0/hk_a0.py index 95fa431..61ad620 100644 --- a/device_package_example/devices/hk_a0/hk_a0.py +++ b/device_package_example/devices/hk_a0/hk_a0.py @@ -6,7 +6,6 @@ except ImportError: BaseROS2DeviceNode = None -# 兼容不同版本 pymodbus try: from pymodbus.client import ModbusSerialClient # 3.x except Exception: @@ -37,59 +36,69 @@ def not_action(func): @device( id="hk_a0", category=["io_module"], - description="HK-A0 模拟输出模块,6通道,Modbus RTU", - display_name="HK-A0 输出模块" + description="华控模拟量输出模块(RS485 Modbus RTU,FC06/03)", + display_name="华控模拟量输出", ) class HKA0: + """华控电子(惠州)RS485 模拟量输出模块驱动。 + + 手册:《模拟量输出系列使用手册(RS485版) V2.0》 + - 保持寄存器 0x000A 起为第 1~12 路输出设定值 + - 固定 3 位小数:1.000 V → 寄存器值 1000(FC06/10 写,FC03 读) + - 配置寄存器:0x0032 站号、0x0033 波特率、0x003D 校验 """ - Huaikong Electronic HK-A0 Analog Output Module Driver (RS485 Modbus RTU) - Supports 6 output channels (AO1-AO6), 12-bit resolution. - Value scaling: Physical Value * 1000 = Register Value. - """ + _ros_node: "BaseROS2DeviceNode" + REG_OUTPUT_BASE = 0x000A + REG_SLAVE_ADDRESS = 0x0032 + REG_BAUDRATE = 0x0033 + REG_PARITY = 0x003D + SCALE = 1000 # 固定 3 位小数 + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): - if device_id is None and 'id' in kwargs: - device_id = kwargs.pop('id') - if config is None and 'config' in kwargs: - config = kwargs.pop('config') + if device_id is None and "id" in kwargs: + device_id = kwargs.pop("id") + if config is None and "config" in kwargs: + config = kwargs.pop("config") self.device_id = device_id or "hk_a0_module_1" self.config = config or {} - - # 日志配置 self.logger = logging.getLogger(f"HKA0.{self.device_id}") - # Modbus 连接参数 self.port = self.config.get("port", "/dev/ttyUSB0") self.baudrate = self.config.get("baudrate", 9600) self.slave_address = self.config.get("slave_address", 1) self.channel_count = self.config.get("channel_count", 6) + self.output_max = float(self.config.get("output_max", 5.0)) self.timeout = self.config.get("timeout", 1.0) - # Modbus 客户端 self.client: Optional[ModbusSerialClient] = None - - # 寄存器地址映射 (根据 HK-A0 手册) - self.REG_OUTPUT_BASE = 0x0009 # 输出寄存器起始地址 - - # Pre-fill self.data self.data = { "status": "Idle", "outputs": [0.0] * self.channel_count, - "last_error": "" + "last_error": "", } @not_action def post_init(self, ros_node: "BaseROS2DeviceNode"): self._ros_node = ros_node + def _channel_register(self, channel: int) -> int: + return self.REG_OUTPUT_BASE + channel - 1 + + def _to_register(self, value: float) -> int: + return int(round(value * self.SCALE)) + + def _from_register(self, raw: int) -> float: + return raw / self.SCALE + @action(description="初始化设备") async def initialize(self) -> bool: - """初始化 Modbus 连接""" + """初始化 Modbus 连接。""" try: if ModbusSerialClient is None: - self.logger.error("pymodbus not installed") + self.logger.error("pymodbus 未安装") self.data["status"] = "Error" self.data["last_error"] = "pymodbus not installed" return False @@ -98,117 +107,118 @@ async def initialize(self) -> bool: port=self.port, baudrate=self.baudrate, timeout=self.timeout, - parity='N', + parity="N", stopbits=1, - bytesize=8 + bytesize=8, ) if not self.client.connect(): - self.logger.error(f"Failed to connect to {self.port}") + self.logger.error(f"无法连接 {self.port}") self.data["status"] = "Error" self.data["last_error"] = "Connection failed" return False self.data["status"] = "Idle" - self.logger.info(f"HK-A0 initialized at {self.port}, Slave Addr: {self.slave_address}") + self.logger.info( + f"华控模拟量输出已连接: {self.port}, 从站 {self.slave_address}, " + f"通道 {self.channel_count}, 量程 0~{self.output_max}" + ) return True except Exception as e: - self.logger.error(f"Initialization error: {e}") + self.logger.error(f"初始化失败: {e}") self.data["status"] = "Error" self.data["last_error"] = str(e) return False @action(description="设置输出值") async def set_output(self, channel: int, value: float) -> bool: - """ - 设置输出值 + """设置单通道输出(FC06 写保持寄存器)。 Args: - channel[通道号]: 通道编号 (1-6) - value[输出值]: 物理值 (0.0-5.0 V) + channel[通道号]: 1 ~ channel_count + value[输出值]: 物理量,电压单位 V(0~5 或 0~10,视模块量程) """ if not (1 <= channel <= self.channel_count): - self.logger.error(f"Invalid channel: {channel}") + self.logger.error(f"无效通道: {channel}") self.data["last_error"] = f"Invalid channel: {channel}" return False - if not (0.0 <= value <= 5.0): - self.logger.error(f"Value out of range: {value}V (must be 0.0-5.0)") - self.data["last_error"] = f"Value out of range: {value}V" + if not (0.0 <= value <= self.output_max): + self.logger.error(f"输出超量程: {value}(允许 0~{self.output_max})") + self.data["last_error"] = f"Value out of range: {value}" return False try: - # 缩放: 1.000V -> 1000 - raw_value = int(value * 1000) - reg_addr = self.REG_OUTPUT_BASE + channel + raw_value = self._to_register(value) + reg_addr = self._channel_register(channel) - # 写入单个保持寄存器 result = self.client.write_register( address=reg_addr, value=raw_value, - slave=self.slave_address + slave=self.slave_address, ) if result.isError(): - self.logger.error(f"Modbus write error for Ch{channel}") + self.logger.error(f"写入通道 {channel} 失败") self.data["last_error"] = "Modbus write error" return False self.data["outputs"][channel - 1] = value - self.logger.info(f"Set HK-A0 Ch{channel} to {value}V (Raw: {raw_value})") + self.logger.info(f"Ch{channel} = {value}(寄存器 {reg_addr:#06x} = {raw_value})") return True except Exception as e: - self.logger.error(f"Error setting output: {e}") + self.logger.error(f"设置输出失败: {e}") self.data["last_error"] = str(e) return False @action(description="停止所有输出") async def stop_all(self) -> bool: - """停止所有通道输出(设置为 0V)""" + """全部通道置 0。""" success = True for i in range(1, self.channel_count + 1): if not await self.set_output(i, 0.0): success = False return success - @action(description="清理资源") - async def cleanup(self) -> bool: - """清理资源,关闭 Modbus 连接""" - try: - if self.client and self.client.is_socket_open(): - self.client.close() - self.data["status"] = "Offline" - self.logger.info("HK-A0 connection closed") - return True - except Exception as e: - self.logger.error(f"Cleanup error: {e}") - return False - @action(description="读取所有输出值") async def read_outputs(self) -> List[float]: - """读取所有通道的当前输出值""" + """读取各通道当前设定值(FC03,自 0x000A 连续读)。""" try: result = self.client.read_holding_registers( - address=self.REG_OUTPUT_BASE + 1, + address=self.REG_OUTPUT_BASE, count=self.channel_count, - slave=self.slave_address + slave=self.slave_address, ) if result.isError(): - self.logger.error("Failed to read outputs") + self.logger.error("读取输出寄存器失败") + self.data["last_error"] = "Modbus read error" return self.data["outputs"] - # 转换为物理值 - outputs = [reg / 1000.0 for reg in result.registers] + outputs = [self._from_register(reg) for reg in result.registers] self.data["outputs"] = outputs return outputs except Exception as e: - self.logger.error(f"Error reading outputs: {e}") + self.logger.error(f"读取输出失败: {e}") + self.data["last_error"] = str(e) return self.data["outputs"] + @action(description="清理资源") + async def cleanup(self) -> bool: + """关闭 Modbus 连接。""" + try: + if self.client and self.client.is_socket_open(): + self.client.close() + self.data["status"] = "Offline" + self.logger.info("华控模拟量输出连接已关闭") + return True + except Exception as e: + self.logger.error(f"清理失败: {e}") + return False + @property @topic_config() def status(self) -> str: @@ -217,4 +227,4 @@ def status(self) -> str: @property @topic_config() def outputs(self) -> List[float]: - return self.data.get("outputs", [0.0]*self.channel_count) + return self.data.get("outputs", [0.0] * self.channel_count) diff --git a/device_package_example/devices/hk_a0/hk_a0.yaml b/device_package_example/devices/hk_a0/hk_a0.yaml index b5880f8..0572053 100644 --- a/device_package_example/devices/hk_a0/hk_a0.yaml +++ b/device_package_example/devices/hk_a0/hk_a0.yaml @@ -99,6 +99,27 @@ hk_a0: title: stop_all参数 type: object type: UniLabJsonCommandAsync + auto-read_outputs: + feedback: {} + goal: {} + goal_default: {} + handles: {} + placeholder_keys: {} + result: {} + schema: + description: '' + properties: + feedback: {} + goal: + properties: {} + required: [] + type: object + result: {} + required: + - goal + title: read_outputs参数 + type: object + type: UniLabJsonCommandAsync module: device_package_example.devices.hk_a0.hk_a0:HKA0 status_types: outputs: String @@ -110,7 +131,7 @@ hk_a0: port: COM3 slave_address: 1 config_info: [] - description: '' + description: 华控 RS485 模拟量输出模块(Modbus RTU,FC06/03/10,寄存器 0x000A 起) handles: [] icon: '' init_param_schema: From 005f202035fd2e59e6b0d5fa7ff21ac0aacc019c Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Fri, 12 Jun 2026 13:01:39 +0800 Subject: [PATCH 08/13] =?UTF-8?q?feat(electrolytic=5Fcell=5Fgripper):=20?= =?UTF-8?q?=E5=A2=9E=E5=8A=A0=E5=8D=95=E8=BD=B4/=E5=A4=B9=E7=88=AA?= =?UTF-8?q?=E6=89=8B=E5=8A=A8=E5=8A=A8=E4=BD=9C=E5=B9=B6=E5=AE=8C=E5=96=84?= =?UTF-8?q?=E4=B8=AD=E6=96=87=E6=B3=A8=E9=87=8A?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Cursor --- .../electrolytic_cell_gripper/README.md | 124 +++++++ .../electrolytic_cell_gripper.py | 328 ++++++++++++------ .../electrolytic_cell_gripper.yaml | 2 +- 3 files changed, 354 insertions(+), 100 deletions(-) create mode 100644 device_package_example/devices/electrolytic_cell_gripper/README.md diff --git a/device_package_example/devices/electrolytic_cell_gripper/README.md b/device_package_example/devices/electrolytic_cell_gripper/README.md new file mode 100644 index 0000000..f73e6fb --- /dev/null +++ b/device_package_example/devices/electrolytic_cell_gripper/README.md @@ -0,0 +1,124 @@ +# 电解池夹爪 + +## 简介 + +电解池夹爪工作站驱动,整合 2 台**俏优灵**步进电机(水平/垂直)与 1 台**大寰** PGE 平行电爪。 + +对外提供两类动作: + +- **工艺动作**:`pick_sample` / `place_sample`(一键完整夹取/放置) +- **手动动作**:`move_motor_mm` / `move_motor_steps` 等(实验人员单轴调试) + +## 设备 ID + +`electrolytic_cell_gripper` + +## 通信方式 + +- 协议:Modbus RTU(RS485),三台设备共用同一串口 +- 默认:115200 baud;电机 slave 1/2,夹爪 slave 5 + +## 依赖 + +- `pyserial` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM29` | 串口号 | +| `baudrate` | `115200` | 波特率 | +| `timeout` | `0.5` | 读超时 (s) | +| `motor1_slave_id` | `1` | 水平电机地址 | +| `motor2_slave_id` | `2` | 垂直电机地址 | +| `gripper_slave_id` | `5` | 夹爪地址 | +| `motor1_steps_per_mm` | 未设 | 水平轴 mm→步 标定(用 `move_motor_mm` 时必填) | +| `motor2_steps_per_mm` | 未设 | 垂直轴 mm→步 标定(用 `move_motor_mm` 时必填) | + +## 主要动作 + +### 工艺动作(实验常规使用) + +- `pick_sample`:夹取样品完整序列 +- `place_sample`:放下样品完整序列 + +### 手动动作(单轴 / 夹爪调试) + +| 动作 | 说明 | +|---|---| +| `move_motor_steps(motor, steps)` | 绝对定位,`motor`:1=水平,2=垂直 | +| `move_motor_mm(motor, mm)` | 按 mm 绝对定位,需 config 标定 `steps_per_mm` | +| `read_motor_position(motor)` | 读当前位置(步) | +| `motor_set_zero(motor)` | 当前位置设为零点 | +| `gripper_open` / `gripper_close` | 夹爪张开 / 闭合 | + +### 通用 + +- `initialize` / `cleanup`:串口连接与释放 +- `emergency_stop`:电机急停 + +## 状态属性 + +`status` + +## Graph 示例 + +`graph_example_electrolytic_cell_gripper.json` + +## 注意事项 + +- **工艺动作**(pick/place)内步数/速度已硬编码,改工艺需改驱动或后续参数化 +- **手动动作**用步数最可靠;mm 需先标定 `motor1_steps_per_mm`、`motor2_steps_per_mm` +- 支持 lazy serial:首次动作时自动打开串口 + +### mm 标定说明 + +俏优灵驱控底层单位为**步**。实验人员习惯用 mm 时,在 graph config 中配置: + +```json +"motor1_steps_per_mm": 2000, +"motor2_steps_per_mm": 2000 +``` + +标定方法:手动走已知距离(如 10 mm),读取 `read_motor_position` 返回的步数,除以 10 得到 `steps_per_mm`。 + +## 产品资料 + +### 产品简介 + +**电解池夹爪工作站**为本实验室定制集成系统,非商用整机。由 **2 台俏优灵步进电机**(水平/垂直滑台)+ **1 台大寰 PGE 平行电爪**组成,经 RS485 Modbus RTU 共用一条总线控制。 + +### 组成与通信 + +| 设备 | 品牌/系列 | Modbus 从站 | 功能 | +|---|---|---|---| +| 水平滑台电机 | 俏优灵 | 1 | X 方向 | +| 垂直滑台电机 | 俏优灵 | 2 | Z 方向 | +| 平行电爪 | 大寰 PGE | 5 | 夹爪开合 | + +- 通信:115200 baud,8N1 +- 高层动作:`pick_sample`(夹取)、`place_sample`(放置) + +### 子设备参考(公开资料) + +**大寰 PGE 系列平行电爪** + +- 工业薄型平行电爪,标配 Modbus RTU(RS485) +- 常用功能码 03/06,24 V DC 供电 +- 具体型号(如 PGE-5-26、PGE-8-14 等)以实验室实物为准 + +**俏优灵步进电机驱控** + +- 深圳市俏优灵科技有限公司 RS485 步进驱控产品 +- 支持 Modbus RTU 位置/速度控制(本驱动使用 FC 03/06/10) +- 具体型号以实验室实物为准 + +### 资料链接 + +- [大寰机器人 PGE 系列产品页](https://www.dh-robotics.com/product/pge) +- [大寰 PGE 系列操作手册 PDF](https://www.dh-robotics.com/wp-content/uploads/2022/12/PGE%E7%B3%BB%E5%88%97%E9%A9%B1%E6%8E%A7%E4%B8%80%E4%BD%93_%E4%BA%A7%E5%93%81%E6%93%8D%E4%BD%9C%E6%89%8B%E5%86%8C_v3.2.pdf) + +### 说明 + +- 运动步数、速度参数已在驱动内按现场工艺硬编码 +- 整机无公开说明书;调试与变更需结合实验室机械与电气文档 diff --git a/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py b/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py index 593bc08..fec2b59 100644 --- a/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py +++ b/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py @@ -1,18 +1,18 @@ """ -Electrolytic Cell Gripper Workstation Driver (电解池夹爪工作站) -Combines 2x QYL stepper motors + 1x DH PGE gripper into a single device -with two high-level actions: pick_sample and place_sample. +电解池夹爪工作站驱动 -All three physical devices share COM29 via RS-485 Modbus RTU. -Motor 1 (slave_id=1), Motor 2 (slave_id=2), Gripper (slave_id=5). +整合 2 台俏优灵步进电机 + 1 台大寰 PGE 平行电爪,对外提供 pick_sample / place_sample 高层动作。 -Communication: 115200, 8N1 -Motor: FC 03/06/10, speed/accel = register raw value (5000 in debug software = reg 5000) -Gripper: FC 03/06 +三台设备共用 RS485 Modbus RTU(默认 COM29): + - 电机 1(从站 1):水平滑台 + - 电机 2(从站 2):垂直滑台 + - 夹爪(从站 5):大寰 PGE -v7: Self-contained driver with lazy serial initialization. - Serial port is opened on first use (not only in initialize()), - so it works regardless of whether the framework calls initialize(). +通信:115200,8N1 +电机:功能码 03/06/10,速度/加速度为寄存器原始值(调试软件填 5000 即写 5000) +夹爪:功能码 03/06 + +v7:自包含驱动,支持延迟打开串口(首次动作时打开,不依赖框架是否调用 initialize)。 """ import logging @@ -52,11 +52,11 @@ def not_action(func): # ═══════════════════════════════════════════════════════════════════ -# CRC16 Modbus +# Modbus CRC16 # ═══════════════════════════════════════════════════════════════════ def _crc16_modbus(data: bytes) -> bytes: - """Calculate Modbus RTU CRC16, returns 2 bytes (low, high).""" + """计算 Modbus RTU CRC16,返回 2 字节(低字节在前)。""" crc = 0xFFFF for byte in data: crc ^= byte @@ -65,21 +65,21 @@ def _crc16_modbus(data: bytes) -> bytes: crc = (crc >> 1) ^ 0xA001 else: crc >>= 1 - return struct.pack(" bytes: @@ -100,7 +100,7 @@ def _build_write_multiple_frame(slave_id: int, start_register: int, values: list frame += struct.pack(">H", v & 0xFFFF) return frame + _crc16_modbus(frame) - # ── Send / Receive ────────────────────────────────────────── + # ── 收发 ────────────────────────────────────────── def send_and_receive(self, frame: bytes, expect_len: int) -> Optional[bytes]: if self._ser is None or not self._ser.is_open: @@ -142,7 +142,7 @@ def send_and_receive(self, frame: bytes, expect_len: int) -> Optional[bytes]: self.logger.warning("Could not locate valid response frame") return raw[:expect_len] if len(raw) >= expect_len else None - # ── High-level register operations ────────────────────────── + # ── 寄存器读写 ────────────────────────────────────────── def read_registers(self, slave_id: int, start: int, count: int = 1) -> Optional[list]: frame = self._build_read_frame(slave_id, start, count) @@ -168,7 +168,7 @@ def write_multiple(self, slave_id: int, start: int, values: list) -> bool: # ═══════════════════════════════════════════════════════════════════ -# Helper: signed 32-bit conversion +# 有符号 32 位整数转换 # ═══════════════════════════════════════════════════════════════════ def _from_signed32(val: int) -> tuple: @@ -176,6 +176,7 @@ def _from_signed32(val: int) -> tuple: val += 0x100000000 return ((val >> 16) & 0xFFFF, val & 0xFFFF) + def _to_signed32(high: int, low: int) -> int: val = (high << 16) | low if val >= 0x80000000: @@ -184,7 +185,7 @@ def _to_signed32(high: int, low: int) -> int: # ═══════════════════════════════════════════════════════════════════ -# Motor register addresses +# 电机寄存器地址(俏优灵) # ═══════════════════════════════════════════════════════════════════ _M_STATUS = 0x0000 @@ -193,21 +194,21 @@ def _to_signed32(high: int, low: int) -> int: _M_SPEED = 0x0003 _M_ESTOP = 0x0004 _M_ENABLE = 0x0006 -_M_PP_TARGET_H = 0x0010 # Point-to-point (absolute) mode +_M_PP_TARGET_H = 0x0010 # 点对点绝对定位模式 _M_PP_TARGET_L = 0x0011 _M_PP_INIT_SPD = 0x0012 _M_PP_RUN_SPD = 0x0013 _M_PP_ACCEL = 0x0014 _M_PP_TOL = 0x0015 _M_HOME = 0x001F -_M_FW_STEPS_H = 0x0040 # Forward (relative) mode +_M_FW_STEPS_H = 0x0040 # 相对定位(正向)模式 _M_FW_STEPS_L = 0x0041 _M_FW_INIT_SPD = 0x0042 _M_FW_RUN_SPD = 0x0043 _M_FW_ACCEL = 0x0044 _M_FW_TOL = 0x0045 -# Gripper register addresses +# 夹爪寄存器地址(大寰 PGE) _G_INIT = 0x0100 _G_FORCE = 0x0101 _G_TARGET_POS = 0x0103 @@ -216,43 +217,43 @@ def _to_signed32(high: int, low: int) -> int: _G_GRIP_STATE = 0x0201 _G_ACTUAL_POS = 0x0202 -# Motor status map +# 电机状态码映射 _MOTOR_STATUS = {0: "Idle", 1: "Busy", 2: "Stopped", 3: "LimitPos", 4: "LimitNeg"} # ═══════════════════════════════════════════════════════════════════ -# Main workstation class +# 工作站主类 # ═══════════════════════════════════════════════════════════════════ @device( id="electrolytic_cell_gripper", category=["custom", "electrolytic_cell_gripper"], - description="电解池夹爪工作站", + description="电解池夹爪工作站(俏优灵电机 + 大寰 PGE 夹爪)", display_name="电解池夹爪", ) class ElectrolyticCellGripper: """ - Electrolytic Cell Gripper Workstation (电解池夹爪). + 电解池夹爪工作站。 - Combines: - - Motor 1 (slave_id=1): Horizontal slide - - Motor 2 (slave_id=2): Vertical slide - - Gripper (slave_id=5): DH PGE parallel gripper + 组成: + - 电机 1(从站 1):俏优灵水平滑台 + - 电机 2(从站 2):俏优灵垂直滑台 + - 夹爪(从站 5):大寰 PGE 平行电爪 - Exposes two high-level actions: - - pick_sample(): Grab a sample from the cell - - place_sample(): Put the sample back + 对外动作分两类: + - 工艺动作:pick_sample / place_sample(完整夹取/放置序列) + - 手动动作:move_motor_mm / move_motor_steps 等(单轴或夹爪调试) - All motion parameters are hardcoded per the validated workflow. + pick/place 中的运动步数按现场工艺硬编码;手动动作由实验人员指定步数或 mm。 """ _ros_node: "BaseROS2DeviceNode" - # Motor speed/accel: user confirmed 5000 = register raw value in debug software - MOTOR_SPEED = 5000 # register raw value - MOTOR_ACCEL = 5000 # register raw value (acceleration time) - MOTOR_INIT_SPD = 50 # initial speed register raw value - MOTOR_TOL = 100 # tolerance in steps + # 电机速度/加速度:调试软件中 5000 对应寄存器原始值 5000 + MOTOR_SPEED = 5000 # 运行速度寄存器值 + MOTOR_ACCEL = 5000 # 加速度寄存器值 + MOTOR_INIT_SPD = 50 # 初始速度寄存器值 + MOTOR_TOL = 100 # 定位容差(步) def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): if device_id is None and "id" in kwargs: @@ -264,7 +265,7 @@ def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwarg self.config = config or {} self.logger = logging.getLogger(f"ECG.{self.device_id}") - # ── Config ────────────────────────────────────────────── + # ── 配置 ────────────────────────────────────────────── self._port_name: str = self.config.get("port", "COM29") self._baudrate: int = int(self.config.get("baudrate", 115200)) self._timeout: float = float(self.config.get("timeout", 0.5)) @@ -272,16 +273,23 @@ def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwarg self._motor1_id: int = int(self.config.get("motor1_slave_id", 1)) self._motor2_id: int = int(self.config.get("motor2_slave_id", 2)) self._gripper_id: int = int(self.config.get("gripper_slave_id", 5)) + self._motor1_steps_per_mm: Optional[float] = self.config.get("motor1_steps_per_mm") + self._motor2_steps_per_mm: Optional[float] = self.config.get("motor2_steps_per_mm") + if self._motor1_steps_per_mm is not None: + self._motor1_steps_per_mm = float(self._motor1_steps_per_mm) + if self._motor2_steps_per_mm is not None: + self._motor2_steps_per_mm = float(self._motor2_steps_per_mm) self._ser: Optional[Serial] = None self._bus: Optional[_ModbusRTU] = None - # ── Data store ────────────────────────────────────────── + # ── 状态数据 ────────────────────────────────────────── self.data: Dict[str, Any] = { "status": "Idle", + "last_error": "", } - # ── Framework hooks ───────────────────────────────────────── + # ── 框架回调 ───────────────────────────────────────── async def _sleep(self, seconds: float): if getattr(self, "_ros_node", None) is not None: @@ -295,10 +303,10 @@ def post_init(self, ros_node: "BaseROS2DeviceNode"): def _ensure_serial(self) -> bool: """ - Lazy serial initialization. - If serial is already open, return True. - If not, try to open it now. This ensures the serial port is available - regardless of whether the framework called initialize() or not. + 延迟打开串口。 + + 若串口已打开则直接返回 True;否则尝试立即打开, + 以便框架未调用 initialize() 时仍能执行动作。 """ if self._bus is not None and self._ser is not None and self._ser.is_open: return True @@ -332,7 +340,7 @@ def _ensure_serial(self) -> bool: @action() async def initialize(self) -> bool: - """Open serial port and verify communication.""" + """打开串口并建立通信。""" self.logger.info("initialize() called") ok = self._ensure_serial() if ok: @@ -345,7 +353,7 @@ async def initialize(self) -> bool: @action() async def cleanup(self) -> bool: - """Close serial port.""" + """关闭串口。""" if self._ser and self._ser.is_open: self._ser.close() self._ser = None @@ -353,27 +361,28 @@ async def cleanup(self) -> bool: self.data["status"] = "Offline" return True - # ── Properties ────────────────────────────────────────────── + # ── 状态属性 ────────────────────────────────────────────── @property @topic_config() def status(self) -> str: return self.data.get("status", "Idle") - # ── Internal motor helpers ────────────────────────────────── + # ── 电机内部方法 ────────────────────────────────── def _motor_set_position_zero(self, slave_id: int) -> bool: - """Write 0 to actual position registers (set current position as zero).""" + """将当前实际位置寄存器写 0(把当前位置设为零点)。""" return self._bus.write_multiple(slave_id, _M_POS_H, [0, 0]) def _motor_move_absolute(self, slave_id: int, position: int, speed: int = None, accel: int = None) -> bool: """ - Move motor to absolute position using point-to-point mode. + 点对点模式绝对定位。 + Args: - position: target in steps (signed 32-bit) - speed: register raw value (default: MOTOR_SPEED=5000) - accel: register raw value (default: MOTOR_ACCEL=5000) + position: 目标位置(步,有符号 32 位) + speed: 运行速度寄存器值(默认 MOTOR_SPEED=5000) + accel: 加速度寄存器值(默认 MOTOR_ACCEL=5000) """ spd = speed if speed is not None else self.MOTOR_SPEED acc = accel if accel is not None else self.MOTOR_ACCEL @@ -382,7 +391,7 @@ def _motor_move_absolute(self, slave_id: int, position: int, return self._bus.write_multiple(slave_id, _M_PP_TARGET_H, values) def _motor_read_status(self, slave_id: int) -> Optional[Dict]: - """Read motor status, position, speed.""" + """读取电机状态、位置、速度。""" regs = self._bus.read_registers(slave_id, _M_STATUS, 4) if regs is None or len(regs) < 4: return None @@ -394,19 +403,19 @@ def _motor_read_status(self, slave_id: int) -> Optional[Dict]: } def _motor_emergency_stop(self, slave_id: int) -> bool: - """Send emergency stop to motor.""" + """发送电机急停。""" return self._bus.write_single(slave_id, _M_ESTOP, 0x0001) async def _motor_wait_idle(self, slave_id: int, timeout: float = 120.0, poll_interval: float = 0.3) -> bool: - """Wait until motor status returns to Idle (0) or non-running state.""" + """轮询直到电机退出 Busy(状态码 1)。""" elapsed = 0.0 motor_name = f"Motor{slave_id}" while elapsed < timeout: info = self._motor_read_status(slave_id) if info is not None: code = info["status_code"] - if code != 1: # Not "Busy" + if code != 1: # 非运行中 self.logger.info(f"{motor_name} idle: pos={info['position']}, status={info['status']}") return True await self._sleep(poll_interval) @@ -414,14 +423,14 @@ async def _motor_wait_idle(self, slave_id: int, timeout: float = 120.0, self.logger.warning(f"{motor_name} wait_idle timed out after {timeout}s") return False - # ── Internal gripper helpers ──────────────────────────────── + # ── 夹爪内部方法 ──────────────────────────────── def _gripper_init(self) -> bool: - """Send homing command (0x01) to gripper.""" + """发送夹爪回零/初始化命令(0x01)。""" return self._bus.write_single(self._gripper_id, _G_INIT, 0x01) async def _gripper_wait_init(self, timeout: float = 30.0) -> bool: - """Wait for gripper initialization to complete.""" + """等待夹爪初始化完成。""" elapsed = 0.0 while elapsed < timeout: regs = self._bus.read_registers(self._gripper_id, _G_INIT_STATE, 1) @@ -442,12 +451,12 @@ def _gripper_set_speed(self, speed: int) -> bool: return self._bus.write_single(self._gripper_id, _G_SPEED, speed) def _gripper_set_position(self, position: int) -> bool: - """Set gripper target position. 0=fully closed, 1000=fully open.""" + """设置夹爪目标位置。0=全闭,1000=全开。""" position = max(0, min(1000, position)) return self._bus.write_single(self._gripper_id, _G_TARGET_POS, position) async def _gripper_wait_done(self, timeout: float = 15.0) -> bool: - """Wait for gripper to finish moving (grip_state != 0).""" + """等待夹爪动作完成(grip_state 为 1/2/3)。""" elapsed = 0.0 while elapsed < timeout: regs = self._bus.read_registers(self._gripper_id, _G_GRIP_STATE, 1) @@ -460,8 +469,129 @@ async def _gripper_wait_done(self, timeout: float = 15.0) -> bool: self.logger.warning("Gripper wait timed out") return False + def _motor_slave_id(self, motor: int) -> Optional[int]: + """motor: 1=水平, 2=垂直""" + if motor == 1: + return self._motor1_id + if motor == 2: + return self._motor2_id + self.logger.error(f"无效电机编号: {motor}(仅支持 1=水平, 2=垂直)") + return None + + def _steps_per_mm(self, motor: int) -> Optional[float]: + return self._motor1_steps_per_mm if motor == 1 else self._motor2_steps_per_mm + + # ═══════════════════════════════════════════════════════════════ + # 实验人员手动动作(单轴 / 夹爪) + # ═══════════════════════════════════════════════════════════════ + + @action(description="单轴绝对定位(步)") + async def move_motor_steps( + self, + motor: int, + steps: int, + wait: bool = True, + speed: int = None, + accel: int = None, + ) -> bool: + """移动指定电机到绝对位置(步)。 + + Args: + motor[电机]: 1=水平, 2=垂直 + steps[步数]: 目标位置(有符号整数) + wait[等待]: 是否等待到位,默认 True + speed[速度]: 可选,运行速度寄存器值 + accel[加速度]: 可选,加速度寄存器值 + """ + if not self._ensure_serial(): + self.data["status"] = "Error" + return False + + slave_id = self._motor_slave_id(motor) + if slave_id is None: + return False + + self.data["status"] = "Busy" + ok = self._motor_move_absolute(slave_id, int(steps), speed=speed, accel=accel) + if ok and wait: + ok = await self._motor_wait_idle(slave_id, timeout=120.0) + self.data["status"] = "Idle" if ok else "Error" + return ok + + @action(description="单轴绝对定位(mm)") + async def move_motor_mm( + self, + motor: int, + mm: float, + wait: bool = True, + speed: int = None, + accel: int = None, + ) -> bool: + """移动指定电机到绝对位置(mm)。 + + 需在 config 中配置 motor1_steps_per_mm / motor2_steps_per_mm(现场标定)。 + """ + steps_per_mm = self._steps_per_mm(motor) + if not steps_per_mm or steps_per_mm <= 0: + self.logger.error( + f"电机 {motor} 未配置 steps_per_mm,请在 graph config 中设置 motor{motor}_steps_per_mm" + ) + self.data["last_error"] = f"motor{motor}_steps_per_mm not configured" + return False + + steps = int(round(mm * steps_per_mm)) + self.logger.info(f"电机 {motor}: {mm} mm -> {steps} 步 (×{steps_per_mm}/mm)") + return await self.move_motor_steps(motor, steps, wait=wait, speed=speed, accel=accel) + + @action(description="读取电机当前位置(步)") + async def read_motor_position(self, motor: int) -> int: + """读取电机当前位置(步)。失败时返回 0。""" + if not self._ensure_serial(): + return 0 + + slave_id = self._motor_slave_id(motor) + if slave_id is None: + return 0 + + info = self._motor_read_status(slave_id) + if info is None: + return 0 + return int(info["position"]) + + @action(description="将电机当前位置设为零点") + async def motor_set_zero(self, motor: int) -> bool: + """把指定电机当前位置写入为零点。""" + if not self._ensure_serial(): + return False + + slave_id = self._motor_slave_id(motor) + if slave_id is None: + return False + + return self._motor_set_position_zero(slave_id) + + @action(description="夹爪张开") + async def gripper_open(self, wait: bool = True) -> bool: + """夹爪全开(位置 1000)。""" + if not self._ensure_serial(): + return False + self._gripper_set_position(1000) + if wait: + return await self._gripper_wait_done(timeout=15.0) + return True + + @action(description="夹爪闭合") + async def gripper_close(self, wait: bool = True) -> bool: + """夹爪全闭(位置 0)。""" + if not self._ensure_serial(): + return False + self._gripper_set_position(0) + if wait: + return await self._gripper_wait_done(timeout=15.0) + return True + # ═══════════════════════════════════════════════════════════════ - # ACTION 1: 夹取样品 (Pick Sample) + # 动作 1:夹取样品(工艺序列) # ═══════════════════════════════════════════════════════════════ @action() @@ -479,7 +609,7 @@ async def pick_sample(self): 9. 1号电机移动到 0 步 10. 2号电机移动到 -630000 步 """ - # ── Lazy serial open ──────────────────────────────────── + # 延迟打开串口 if not self._ensure_serial(): self.logger.error("pick_sample ABORTED: cannot open serial port") self.data["status"] = "Error" @@ -491,57 +621,57 @@ async def pick_sample(self): self.logger.info("=" * 60) try: - # Step 1: Gripper init (homing) - self.logger.info("[1/11] Gripper init (homing)...") + # 步骤 1:夹爪回零 + self.logger.info("[1/10] Gripper init (homing)...") self._gripper_init() await self._gripper_wait_init(timeout=30.0) - # Step 2: Set gripper force 50% - self.logger.info("[2/11] Set gripper force = 50%") + # 步骤 2:夹爪力 50% + self.logger.info("[2/10] Set gripper force = 50%") self._gripper_set_force(50) time_module.sleep(0.05) - # Step 3: Set gripper speed 100% - self.logger.info("[3/11] Set gripper speed = 100%") + # 步骤 3:夹爪速度 100% + self.logger.info("[3/10] Set gripper speed = 100%") self._gripper_set_speed(100) time_module.sleep(0.05) - # Step 4: Both motors set current position as zero - self.logger.info("[4/11] Motor1 + Motor2 set position zero") + # 步骤 4:两轴当前位置设为零点 + self.logger.info("[4/10] Motor1 + Motor2 set position zero") self._motor_set_position_zero(self._motor1_id) time_module.sleep(0.05) self._motor_set_position_zero(self._motor2_id) time_module.sleep(0.05) - # Step 5: Motor 1 move to 838000 - self.logger.info("[5/11] Motor1 move to 838000 steps (speed=5000, accel=5000)") + # 步骤 5:水平轴到 838000 步 + self.logger.info("[5/10] Motor1 move to 838000 steps (speed=5000, accel=5000)") self._motor_move_absolute(self._motor1_id, 838000, speed=5000, accel=5000) await self._motor_wait_idle(self._motor1_id, timeout=120.0) - # Step 6: Motor 2 move to -800000 - self.logger.info("[6/11] Motor2 move to -800000 steps") + # 步骤 6:垂直轴到 -800000 步 + self.logger.info("[6/10] Motor2 move to -800000 steps") self._motor_move_absolute(self._motor2_id, -800000, speed=5000, accel=5000) await self._motor_wait_idle(self._motor2_id, timeout=120.0) - # Step 7: Gripper close (position=0) - self.logger.info("[7/11] Gripper close") + # 步骤 7:夹爪闭合(位置 0) + self.logger.info("[7/10] Gripper close") self._gripper_set_position(0) await self._gripper_wait_done(timeout=15.0) - # Step 8: Motor 2 move to 0 - self.logger.info("[8/11] Motor2 move to 0 steps") + # 步骤 8:垂直轴回 0 + self.logger.info("[8/10] Motor2 move to 0 steps") self._motor_move_absolute(self._motor2_id, 0, speed=5000, accel=5000) await self._motor_wait_idle(self._motor2_id, timeout=120.0) - # Step 9: Motor 1 move to 0 - self.logger.info("[9/11] Motor1 move to 0 steps") + # 步骤 9:水平轴回 0 + self.logger.info("[9/10] Motor1 move to 0 steps") self._motor_move_absolute(self._motor1_id, 0, speed=5000, accel=5000) await self._motor_wait_idle(self._motor1_id, timeout=120.0) - # Step 10: Motor 2 move to -850000 - # self.logger.info("[10/11] Motor2 move to -850000 steps") + # 步骤 10:垂直轴到待机位 -630000(旧值 -850000 已弃用) + # self.logger.info("[10/10] Motor2 move to -850000 steps") # self._motor_move_absolute(self._motor2_id, -850000, speed=5000, accel=5000) - self.logger.info("[10/11] Motor2 move to -630000 steps") + self.logger.info("[10/10] Motor2 move to -630000 steps") self._motor_move_absolute(self._motor2_id, -630000, speed=5000, accel=5000) await self._motor_wait_idle(self._motor2_id, timeout=120.0) @@ -555,7 +685,7 @@ async def pick_sample(self): self.data["status"] = "Error" # ═══════════════════════════════════════════════════════════════ - # ACTION 2: 放下样品 (Place Sample) + # 动作 2:放下样品(工艺序列) # ═══════════════════════════════════════════════════════════════ @action() @@ -569,7 +699,7 @@ async def place_sample(self): 5. 2号电机移动到 0 步 6. 1号电机移动到 0 步 """ - # ── Lazy serial open ──────────────────────────────────── + # 延迟打开串口 if not self._ensure_serial(): self.logger.error("place_sample ABORTED: cannot open serial port") self.data["status"] = "Error" @@ -581,32 +711,32 @@ async def place_sample(self): self.logger.info("=" * 60) try: - # Step 1: Motor 2 move to 0 + # 步骤 1:垂直轴到 0 self.logger.info("[1/6] Motor2 move to 0 steps") self._motor_move_absolute(self._motor2_id, 0, speed=5000, accel=5000) await self._motor_wait_idle(self._motor2_id, timeout=120.0) - # Step 2: Motor 1 move to 838000 + # 步骤 2:水平轴到 838000 步 self.logger.info("[2/6] Motor1 move to 838000 steps") self._motor_move_absolute(self._motor1_id, 838000, speed=5000, accel=5000) await self._motor_wait_idle(self._motor1_id, timeout=120.0) - # Step 3: Motor 2 move to -790000 + # 步骤 3:垂直轴下探 -790000 步 self.logger.info("[3/6] Motor2 move to -790000 steps") self._motor_move_absolute(self._motor2_id, -790000, speed=5000, accel=5000) await self._motor_wait_idle(self._motor2_id, timeout=120.0) - # Step 4: Gripper open (position=1000) + # 步骤 4:夹爪张开(位置 1000) self.logger.info("[4/6] Gripper open") self._gripper_set_position(1000) await self._gripper_wait_done(timeout=15.0) - # Step 5: Motor 2 move to 0 + # 步骤 5:垂直轴回 0 self.logger.info("[5/6] Motor2 move to 0 steps") self._motor_move_absolute(self._motor2_id, 0, speed=5000, accel=5000) await self._motor_wait_idle(self._motor2_id, timeout=120.0) - # Step 6: Motor 1 move to 0 + # 步骤 6:水平轴回 0 self.logger.info("[6/6] Motor1 move to 0 steps") self._motor_move_absolute(self._motor1_id, 0, speed=5000, accel=5000) await self._motor_wait_idle(self._motor1_id, timeout=120.0) @@ -621,12 +751,12 @@ async def place_sample(self): self.data["status"] = "Error" # ═══════════════════════════════════════════════════════════════ - # Emergency stop + # 急停 # ═══════════════════════════════════════════════════════════════ @action() async def emergency_stop(self): - """Emergency stop all motors immediately.""" + """立即停止所有电机(夹爪不动作)。""" self.logger.warning("EMERGENCY STOP") if self._bus is not None: self._motor_emergency_stop(self._motor1_id) diff --git a/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.yaml b/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.yaml index 976f633..126e9aa 100644 --- a/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.yaml +++ b/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.yaml @@ -158,7 +158,7 @@ electrolytic_cell_gripper: status: str type: python config_info: [] - description: '' + description: 电解池夹爪工作站(2×俏优灵步进电机 + 大寰 PGE 平行电爪,RS485 Modbus RTU) handles: [] icon: '' init_param_schema: From 6bad6fb97487d327cacfb3d270b240704a45fd09 Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Fri, 12 Jun 2026 13:01:42 +0800 Subject: [PATCH 09/13] =?UTF-8?q?docs(daheng=5Fhd=5Fr630c):=20=E5=AF=B9?= =?UTF-8?q?=E9=BD=90=E5=A4=A7=E6=81=92=20HD-R630C-U3=20=E4=BA=A7=E5=93=81?= =?UTF-8?q?=E6=8F=8F=E8=BF=B0?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Cursor --- .../devices/daheng_hd_r630c/README.md | 100 ++++++++++++++++++ .../daheng_hd_r630c/daheng_hd_r630c.py | 5 +- .../daheng_hd_r630c/daheng_hd_r630c.yaml | 2 +- .../graph_example_daheng_hd_r630c.json | 2 +- 4 files changed, 105 insertions(+), 4 deletions(-) create mode 100644 device_package_example/devices/daheng_hd_r630c/README.md diff --git a/device_package_example/devices/daheng_hd_r630c/README.md b/device_package_example/devices/daheng_hd_r630c/README.md new file mode 100644 index 0000000..42a4618 --- /dev/null +++ b/device_package_example/devices/daheng_hd_r630c/README.md @@ -0,0 +1,100 @@ +# HD-R630C 工业相机 + +## 简介 + +大恒图像 **HD-R630C-U3** USB3.0 彩色工业相机驱动,基于 Harvesters + GenICam(USB3 Vision)接口。 + +## 设备 ID + +`daheng_hd_r630c` + +## 通信方式 + +- 协议:USB3 Vision(GenTL Producer) +- 默认 CTI:`C:\Program Files (x86)\Do3think\DVP2 x64\DVPCameraTL64.cti` + +## 依赖 + +- `harvesters` +- `numpy` +- `opencv-python-headless` 或 `pillow`(保存图片) + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `cti_path` | 见上 | GenTL Producer 路径 | +| `device_index` | `0` | 相机索引 | +| `default_exposure_time` | `10000.0` | 默认曝光 (μs) | +| `default_gain` | `0.0` | 默认增益 (dB) | +| `save_dir` | `./captured_images` | 截图保存目录 | + +## 主要动作 + +- `initialize` / `cleanup`:打开/关闭相机 +- `snap`:单帧采集,返回图片文件路径 +- `start_stream` / `stop_stream`:连续采集 +- `set_exposure_time` / `set_gain`:参数调节 + +## 状态属性 + +`status`、`exposure_time`、`gain`、`frame_rate`、`image_width`、`image_height`、`is_streaming`、`last_frame_id`、`last_image_path` + +## Graph 示例 + +`graph_example_daheng_hd_r630c.json` + +## 注意事项 + +- 需安装相机 SDK 及 GenTL `.cti` 文件(本实验室使用度申 DVP GenTL) +- 默认路径为 Windows,Linux/macOS 需修改 `cti_path` + +## 产品资料 + +### 产品简介 + +**HD-R630C-U3** 为大恒图像(Daheng Imaging)6.3 MP USB3.0 彩色工业面阵相机,体积 29 mm 立方,适用于机器视觉与实验室成像。与同平台度申 M3ST630-H-O2C 规格相近,本驱动通过 GenICam 接口控制,与具体销售品牌无关。 + +### 产品特点 + +- 3072 × 2048 分辨率,最高 70 FPS +- 1/1.8" 卷帘快门 CMOS,像元 2.4 μm +- 软件/硬件触发,12 bit 输出 +- USB 3.0 带锁紧螺口,5 V 供电 + +### 技术参数(HD-R630C-U3,参考大恒图像规格) + +| 项目 | 参数 | +|---|---| +| 型号 | HD-R630C-U3 | +| 生产厂家 | 大恒图像(Daheng Imaging) | +| 分辨率 | 3072 × 2048 | +| 靶面 | 1/1.8" | +| 快门类型 | 卷帘快门 | +| 像元尺寸 | 2.4 μm | +| 最大帧率 | 70 FPS | +| 黑白/彩色 | 彩色 | +| 感光区面积 | 7.37 × 4.91 mm | +| 信噪比 | 36.99 dB | +| 灵敏度 | 0.425 V/lux·s(1/30 s,F5.6) | +| 位深 | 12 bit | +| 触发方式 | 软件触发 / 硬件触发 | +| 动态范围 | 71 dB | +| 光谱响应 | 390 ~ 650 nm | +| 曝光时间 | 6 μs ~ 约 6 s | +| 增益范围 | 1 ~ 15.875×(步进 0.125×) | +| 供电 | USB 5 V | +| 典型功耗 | 工作 1.64 W / 待机 1.12 W | +| 传输接口 | USB 3.0(带紧固螺口) | +| 镜头接口 | C-Mount | +| 外形尺寸 | 29 × 29 × 29 mm | +| 工作温度 | -10 ~ 50 ℃ | +| 重量 | 40 g | + +### 资料链接 + +- [大恒图像官网](https://www.daheng-imaging.com/) +- [度申 M3ST630-H-O2C(同平台参考)](https://en.do3think.com/product/m3st630-h-o2c-area-scan-camera) +- [度申 M3ST 系列概览](https://www.do3think.com/M3S/) + +> 说明:本实验室驱动使用 Harvesters + 度申 GenTL(`DVPCameraTL64.cti`)。若使用大恒官方 SDK,需相应调整 `cti_path`。 diff --git a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py index 3484b65..6e8151d 100644 --- a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py +++ b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py @@ -39,14 +39,15 @@ def not_action(func): @device( id="daheng_hd_r630c", category=["sensor", "daheng_hd_r630c"], - description="度申 HD-R630C USB3 工业相机", + description="大恒图像 HD-R630C-U3 USB3 工业相机", display_name="HD-R630C 工业相机", ) class DahengHdR630c: - """度申 DO3THINK M3S630-H-O2C (HD-R630C-U3) USB3 Vision 彩色工业相机驱动。 + """大恒图像 HD-R630C-U3 USB3 Vision 彩色工业相机驱动。 通过 Harvesters (GenICam/GenTL) 通用接口与相机通信,支持单帧采集、 连续采集、曝光时间和增益设置等功能。 + 本实验室 GenTL 使用度申 DVP SDK(`DVPCameraTL64.cti`)。 依赖: - harvesters: pip install harvesters diff --git a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml index a8c1352..fc998d0 100644 --- a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml +++ b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml @@ -297,7 +297,7 @@ daheng_hd_r630c: status: str type: python config_info: [] - description: 度申 DO3THINK M3S630-H-O2C (HD-R630C-U3) USB3 Vision 彩色工业相机 + description: 大恒图像 HD-R630C-U3 USB3 Vision 彩色工业相机(GenICam / USB3 Vision) handles: [] icon: '' init_param_schema: diff --git a/device_package_example/devices/daheng_hd_r630c/graph_example_daheng_hd_r630c.json b/device_package_example/devices/daheng_hd_r630c/graph_example_daheng_hd_r630c.json index d16a55a..75d5a76 100644 --- a/device_package_example/devices/daheng_hd_r630c/graph_example_daheng_hd_r630c.json +++ b/device_package_example/devices/daheng_hd_r630c/graph_example_daheng_hd_r630c.json @@ -2,7 +2,7 @@ "nodes": [ { "id": "daheng_camera_1", - "name": "度申 M3S630-H-O2C 工业相机", + "name": "大恒 HD-R630C-U3 工业相机", "children": [], "parent": null, "type": "device", From 967ff2dcdf5c82e506ea66a33125eaf4e5512305 Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Fri, 12 Jun 2026 13:01:42 +0800 Subject: [PATCH 10/13] =?UTF-8?q?docs(duco=5Fgcr5):=20=E4=BF=AE=E6=AD=A3?= =?UTF-8?q?=E5=A4=9A=E5=8F=AF=20DUCO=20=E5=93=81=E7=89=8C=E5=BD=92?= =?UTF-8?q?=E5=B1=9E=E8=AF=B4=E6=98=8E?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Cursor --- .../devices/duco_gcr5/README.md | 76 +++++++++++++++++++ .../devices/duco_gcr5/duco_gcr5.py | 2 +- .../devices/duco_gcr5/duco_gcr5.yaml | 2 +- 3 files changed, 78 insertions(+), 2 deletions(-) create mode 100644 device_package_example/devices/duco_gcr5/README.md diff --git a/device_package_example/devices/duco_gcr5/README.md b/device_package_example/devices/duco_gcr5/README.md new file mode 100644 index 0000000..b5be810 --- /dev/null +++ b/device_package_example/devices/duco_gcr5/README.md @@ -0,0 +1,76 @@ +# DUCO 协作机器人 + +## 简介 + +新松 DUCO GCR5-910 协作机器人驱动,TCP 2000 端口纯文本协议,支持上电、使能、运行程序与速度调节。 + +> 多可(DUCO)源自中科新松有限公司,为国内新松旗下智能机器人子品牌。 + +## 设备 ID + +`duco_gcr5` + +## 通信方式 + +- 协议:TCP 文本命令 +- 默认:命令端口 2000,状态端口 2001 + +## 依赖 + +无额外 Python 包(标准库 `socket`) + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `ip` | `192.168.1.10` | 机器人 IP | +| `cmd_port` | `2000` | 命令端口 | +| `status_port` | `2001` | 状态推送端口 | +| `timeout` | `5.0` | 连接超时 (s) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与断开 +- `power_on` / `power_off` / `enable` / `disable`:电源与使能 +- `run_program` / `stop` / `set_speed`:程序与速度控制 + +## 状态属性 + +机器人状态、程序状态、操作模式等(见驱动 `data` 字段) + +## Graph 示例 + +`graph_example_duco_gcr5.json` + +## 注意事项 + +- 需与机器人在同一网段 +- 运行程序前需完成上电与使能流程 + +## 产品资料 + +### 产品简介 + +**多可(DUCO)** 源自中科新松有限公司,是国内新松旗下智能机器人子品牌。**GCR5-910** 为其 6 轴协作机器人,额定负载 5 kg,工作半径 917 mm,适用于涂胶、装配、检测、上下料等场景。本驱动通过 TCP 2000 端口文本协议控制。 + +### 技术参数 + +| 项目 | 参数 | +|---|---| +| 自由度 | 6 | +| 额定负载 | 5 kg | +| 工作半径 | 917 mm | +| 重复定位精度 | ±0.02 mm | +| 末端最大速度 | 3.6 m/s | +| 直线最大速度 | 1.5 m/s | +| 关节速度 | 225 °/s | +| 防护等级 | IP54 / IP65 | +| 典型功耗 | 200 W | +| 通信 | TCP/IP、Modbus/TCP、Profinet、Ethernet/IP | +| 净重 | 22 kg | +| 品牌/厂商 | 多可 DUCO(中科新松 / 新松智能机器人子品牌) | + +### 资料链接 + +- [DUCO 多可 GCR5-910 官网](https://ducorobots.cn/prodetail/2.html) +- [DUCO GCR5-910 英文规格](https://www.ducorobots.com/Gcr-series-cobot/gcr5-910) diff --git a/device_package_example/devices/duco_gcr5/duco_gcr5.py b/device_package_example/devices/duco_gcr5/duco_gcr5.py index 668acfd..8e22335 100644 --- a/device_package_example/devices/duco_gcr5/duco_gcr5.py +++ b/device_package_example/devices/duco_gcr5/duco_gcr5.py @@ -56,7 +56,7 @@ def not_action(func): display_name="DUCO 协作机器人" ) class DucoGCR5: - """新松 DUCO GCR5-910 协作机器人驱动(TCP 2000 文本协议版)""" + """多可 DUCO GCR5-910 协作机器人驱动(中科新松 / 新松智能机器人子品牌,TCP 2000 文本协议)""" _ros_node: "BaseROS2DeviceNode" diff --git a/device_package_example/devices/duco_gcr5/duco_gcr5.yaml b/device_package_example/devices/duco_gcr5/duco_gcr5.yaml index 5b7fadc..9c6ad7e 100644 --- a/device_package_example/devices/duco_gcr5/duco_gcr5.yaml +++ b/device_package_example/devices/duco_gcr5/duco_gcr5.yaml @@ -330,7 +330,7 @@ duco_gcr5: tcp_pose: String type: python config_info: [] - description: 新松 DUCO GCR5-910 协作机器人(TCP 2000 端口文本协议) + description: 多可 DUCO GCR5-910 协作机器人(中科新松 / 新松智能机器人子品牌,TCP 2000 文本协议) handles: [] icon: '' id: duco_gcr5 From 239e97940677e61c10bf48711d51b37966647968 Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Fri, 12 Jun 2026 13:01:43 +0800 Subject: [PATCH 11/13] =?UTF-8?q?fix(jyhsm):=20=E7=BB=9F=E4=B8=80=E4=B9=85?= =?UTF-8?q?=E8=B7=83=E4=BA=A7=E5=93=81=E5=9E=8B=E5=8F=B7=E4=B8=BA=20JY-HSM?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Cursor --- .../jyhsm_temperature_transmitter/README.md | 74 +++++++++++++++++++ ...example_jyhsm_temperature_transmitter.json | 2 +- .../jyhsm_temperature_transmitter.py | 8 +- .../jyhsm_temperature_transmitter.yaml | 2 +- .../graph_combined_lab.json | 2 +- 5 files changed, 81 insertions(+), 7 deletions(-) create mode 100644 device_package_example/devices/jyhsm_temperature_transmitter/README.md diff --git a/device_package_example/devices/jyhsm_temperature_transmitter/README.md b/device_package_example/devices/jyhsm_temperature_transmitter/README.md new file mode 100644 index 0000000..32fd5fc --- /dev/null +++ b/device_package_example/devices/jyhsm_temperature_transmitter/README.md @@ -0,0 +1,74 @@ +# JY-HSM 温度变送器 + +## 简介 + +安徽久跃 JY-HSM 一体化温度变送器驱动,Modbus RTU 读取实时温度,支持阈值监控与提醒。 + +## 设备 ID + +`jyhsm_temperature_transmitter` + +## 通信方式 + +- 协议:Modbus RTU(RS485) +- 默认:9600 baud,8N1,从站地址 1 + +## 依赖 + +- `pyserial` + +## 配置参数 + +| 参数 | 默认值 | 说明 | +|---|---|---| +| `port` | `COM4` | 串口号 | +| `baudrate` | `9600` | 波特率 | +| `slave_address` | `1` | Modbus 从站地址 | +| `timeout` | `1.0` | 通信超时 (s) | + +## 主要动作 + +- `initialize` / `cleanup`:连接与释放 +- 温度读取、阈值设置与监控(见驱动与 YAML) + +## 状态属性 + +`status`、`temperature`、`target_temperature`、`alarm` 等 + +## Graph 示例 + +`graph_example_jyhsm_temperature_transmitter.json` + +## 注意事项 + +- 寄存器 0x0000 为实时值 ×100(有符号整型) +- 浮点温度见 0x0002–0x0003(ABCD 格式) + +## 产品资料 + +### 产品简介 + +**JY-HSM** 一体化温度变送器由安徽久跃仪表有限公司生产,将 Pt100/Pt1000 或热电偶信号转换为 Modbus 数字量或 4–20 mA 等输出,适用于工业现场温度监测。 + +### 产品特点 + +- 不锈钢封装,体积小巧,抗震性好 +- 支持 RS485 Modbus RTU(本驱动) +- 可选 4–20 mA、0–10 V、0–5 V 输出型号 + +### 技术参数(JY-HSM 系列参考) + +| 项目 | 参数 | +|---|---| +| 测量范围 | -200 ~ 1200 ℃(视传感器) | +| 准确度 | 0.2 ~ 0.5 ℃ / FS | +| 供电 | 12 ~ 36 V DC(常用 24 V) | +| 输出 | 4–20 mA / RS485 / 0–10 V 等 | +| 防护等级 | IP65 | +| 外壳材质 | 不锈钢 | +| 生产厂家 | 安徽久跃仪表有限公司 | + +### 资料链接 + +- [久跃 JY-HSM 赫斯曼温度变送器](http://www.jiuyueyb.com/Products-14629713.html) +- [久跃一体化防爆温度变送器系列](http://www.jiuyueyb.com/SonList-620537.html) diff --git a/device_package_example/devices/jyhsm_temperature_transmitter/graph_example_jyhsm_temperature_transmitter.json b/device_package_example/devices/jyhsm_temperature_transmitter/graph_example_jyhsm_temperature_transmitter.json index 7317199..d155046 100644 --- a/device_package_example/devices/jyhsm_temperature_transmitter/graph_example_jyhsm_temperature_transmitter.json +++ b/device_package_example/devices/jyhsm_temperature_transmitter/graph_example_jyhsm_temperature_transmitter.json @@ -2,7 +2,7 @@ "nodes": [ { "id": "jyhsm_temp_1", - "name": "JYHSM一体化温度变送器", + "name": "JY-HSM 一体化温度变送器", "children": [], "parent": null, "type": "device", diff --git a/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py index 2d62150..b8f2cdb 100644 --- a/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py +++ b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py @@ -1,5 +1,5 @@ """ -JYHSM 一体化温度变送器驱动 +JY-HSM 一体化温度变送器驱动 厂家:安徽久跃仪表有限公司 通信协议:Modbus RTU (RS485) 默认参数:9600, 8N1, 从站地址 1 @@ -182,12 +182,12 @@ def _encode_float_abcd(value: float) -> tuple: @device( id="jyhsm_temperature_transmitter", category=["temperature"], - description="JYHSM 一体化温度变送器,Modbus RTU", - display_name="JYHSM 温度变送器" + description="JY-HSM 一体化温度变送器,Modbus RTU", + display_name="JY-HSM 温度变送器" ) class JyhsmTemperatureTransmitter: """ - JYHSM 一体化温度变送器 Modbus RTU 驱动 + JY-HSM 一体化温度变送器 Modbus RTU 驱动 (所有数值类型均对齐为 float 以支持 Uni-Lab-OS 框架) 新增功能: diff --git a/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml index d82dc2e..a0a8886 100644 --- a/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml +++ b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.yaml @@ -52,7 +52,7 @@ jyhsm_temperature_transmitter: tolerance: float timeout: float config_info: [] - description: JYHSM一体化温度变送器,安徽久跃仪表有限公司生产。通过Modbus RTU协议(RS485)通信,支持实时温度监测、温度偏移校准、单位切换等功能。新增温度阈值监控功能,可设置目标温度并在达到时触发提醒,适用于实验过程监控和自动化工作流。 + description: JY-HSM 一体化温度变送器,安徽久跃仪表有限公司生产。通过 Modbus RTU 协议(RS485)通信,支持实时温度监测、温度偏移校准、单位切换等功能。新增温度阈值监控功能,可设置目标温度并在达到时触发提醒,适用于实验过程监控和自动化工作流。 handles: [] icon: '' init_param_schema: diff --git a/device_package_example/graph_combined_lab.json b/device_package_example/graph_combined_lab.json index ea428f1..b0c4350 100644 --- a/device_package_example/graph_combined_lab.json +++ b/device_package_example/graph_combined_lab.json @@ -40,7 +40,7 @@ }, { "id": "jyhsm_temp_1", - "name": "JYHSM一体化温度变送器", + "name": "JY-HSM 一体化温度变送器", "children": [], "parent": null, "type": "device", From 45769292c8c333fb4a9c1d377efda4fa3fea6e08 Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Fri, 12 Jun 2026 13:18:31 +0800 Subject: [PATCH 12/13] =?UTF-8?q?docs(daheng=5Fhd=5Fr630c):=20=E8=A1=A5?= =?UTF-8?q?=E5=85=85=E5=BA=A6=E7=94=B3=E4=BB=A3=E5=B7=A5=E8=B4=B4=E7=89=8C?= =?UTF-8?q?=E4=B8=8E=20SDK=20=E8=AF=B4=E6=98=8E?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Cursor --- .../devices/daheng_hd_r630c/README.md | 15 ++++++++------- .../devices/daheng_hd_r630c/daheng_hd_r630c.py | 8 ++++---- .../devices/daheng_hd_r630c/daheng_hd_r630c.yaml | 2 +- 3 files changed, 13 insertions(+), 12 deletions(-) diff --git a/device_package_example/devices/daheng_hd_r630c/README.md b/device_package_example/devices/daheng_hd_r630c/README.md index 42a4618..22a287f 100644 --- a/device_package_example/devices/daheng_hd_r630c/README.md +++ b/device_package_example/devices/daheng_hd_r630c/README.md @@ -2,7 +2,7 @@ ## 简介 -大恒图像 **HD-R630C-U3** USB3.0 彩色工业相机驱动,基于 Harvesters + GenICam(USB3 Vision)接口。 +实验室设备铭牌为 **大恒 HD-R630C-U3** USB3.0 彩色工业相机;据现场开发人员说明,该机本质为度申科技生产、大恒光电贴牌销售,**接入时使用度申 DVP 开发包**(GenTL)。本驱动基于 Harvesters + GenICam(USB3 Vision)接口,默认加载度申 `DVPCameraTL64.cti`。 ## 设备 ID @@ -46,14 +46,15 @@ ## 注意事项 -- 需安装相机 SDK 及 GenTL `.cti` 文件(本实验室使用度申 DVP GenTL) -- 默认路径为 Windows,Linux/macOS 需修改 `cti_path` +- 需安装**度申 DVP SDK** 及 GenTL `.cti` 文件(非大恒 Galaxy SDK) +- 贴牌关系:销售型号为大恒 HD-R630C-U3,底层与度申同平台相机一致,故沿用度申开发包接入 +- 默认 `cti_path` 为 Windows,Linux/macOS 需按实际安装路径修改 ## 产品资料 ### 产品简介 -**HD-R630C-U3** 为大恒图像(Daheng Imaging)6.3 MP USB3.0 彩色工业面阵相机,体积 29 mm 立方,适用于机器视觉与实验室成像。与同平台度申 M3ST630-H-O2C 规格相近,本驱动通过 GenICam 接口控制,与具体销售品牌无关。 +**HD-R630C-U3** 为大恒光电贴牌销售的 6.3 MP USB3.0 彩色工业面阵相机;现场接入确认其由**度申科技**生产,与同平台度申 M3ST630-H-O2C 规格相近。本驱动通过 Harvesters + 度申 GenTL 控制,设备 ID 保留 `daheng_hd_r630c` 以对应实验室铭牌与 graph 配置。 ### 产品特点 @@ -66,8 +67,8 @@ | 项目 | 参数 | |---|---| -| 型号 | HD-R630C-U3 | -| 生产厂家 | 大恒图像(Daheng Imaging) | +| 销售型号 | HD-R630C-U3(大恒光电贴牌) | +| 生产厂家 | 度申科技(Do3think);大恒光电贴牌销售 | | 分辨率 | 3072 × 2048 | | 靶面 | 1/1.8" | | 快门类型 | 卷帘快门 | @@ -97,4 +98,4 @@ - [度申 M3ST630-H-O2C(同平台参考)](https://en.do3think.com/product/m3st630-h-o2c-area-scan-camera) - [度申 M3ST 系列概览](https://www.do3think.com/M3S/) -> 说明:本实验室驱动使用 Harvesters + 度申 GenTL(`DVPCameraTL64.cti`)。若使用大恒官方 SDK,需相应调整 `cti_path`。 +> 说明:本实验室按开发人员原始接入方式,使用 Harvesters + **度申 DVP GenTL**(`DVPCameraTL64.cti`),与大恒贴牌、度申代工的关系一致,无需改用大恒 Galaxy SDK。 diff --git a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py index 6e8151d..0354c9c 100644 --- a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py +++ b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py @@ -39,15 +39,15 @@ def not_action(func): @device( id="daheng_hd_r630c", category=["sensor", "daheng_hd_r630c"], - description="大恒图像 HD-R630C-U3 USB3 工业相机", + description="大恒贴牌 HD-R630C-U3(度申代工,度申 DVP SDK 接入)", display_name="HD-R630C 工业相机", ) class DahengHdR630c: - """大恒图像 HD-R630C-U3 USB3 Vision 彩色工业相机驱动。 + """大恒 HD-R630C-U3 USB3 Vision 彩色工业相机驱动(度申代工贴牌)。 - 通过 Harvesters (GenICam/GenTL) 通用接口与相机通信,支持单帧采集、 + 现场设备铭牌为大恒 HD-R630C-U3,本质为度申科技生产、大恒光电贴牌销售; + 接入时使用度申 DVP 开发包(GenTL)。通过 Harvesters 与相机通信,支持单帧采集、 连续采集、曝光时间和增益设置等功能。 - 本实验室 GenTL 使用度申 DVP SDK(`DVPCameraTL64.cti`)。 依赖: - harvesters: pip install harvesters diff --git a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml index fc998d0..c87c174 100644 --- a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml +++ b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.yaml @@ -297,7 +297,7 @@ daheng_hd_r630c: status: str type: python config_info: [] - description: 大恒图像 HD-R630C-U3 USB3 Vision 彩色工业相机(GenICam / USB3 Vision) + description: 大恒贴牌 HD-R630C-U3(度申代工,Harvesters + 度申 DVP GenTL) handles: [] icon: '' init_param_schema: From e314e190e8cd300df9cf308ce15b3dcada11846d Mon Sep 17 00:00:00 2001 From: ZiWei <131428629+ZiWei09@users.noreply.github.com> Date: Fri, 12 Jun 2026 13:22:49 +0800 Subject: [PATCH 13/13] =?UTF-8?q?feat(devices):=20=E6=B7=BB=E5=8A=A0?= =?UTF-8?q?=E6=9C=AC=E5=9C=B0=E7=A1=AC=E4=BB=B6=E5=86=92=E7=83=9F=E6=B5=8B?= =?UTF-8?q?=E8=AF=95=E5=85=A5=E5=8F=A3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit 为 16 个设备驱动补充标准化 __main__ 冒烟脚本与 smoke_runner 工具,便于用户插上硬件后快速验证驱动通信与控制。 Co-authored-by: Cursor --- README.md | 17 +- device_package_example/SMOKE_TEST.md | 97 +++ .../devices/bronkhorst_el_flow/README.md | 11 + .../bronkhorst_el_flow/bronkhorst_el_flow.py | 604 ++++++++++-------- .../devices/chi760e/README.md | 11 + .../devices/chi760e/chi760e.py | 45 ++ .../devices/cmos_detector/README.md | 11 + .../devices/cmos_detector/cmos_detector.py | 41 ++ .../devices/cni_laser_msl_u_532/README.md | 11 + .../cni_laser_msl_u_532.py | 42 ++ .../devices/daheng_gci060505/README.md | 11 + .../daheng_gci060505/daheng_gci060505.py | 50 ++ .../devices/daheng_hd_r630c/README.md | 11 + .../daheng_hd_r630c/daheng_hd_r630c.py | 50 ++ .../devices/dhjf_circulation_bath/README.md | 11 + .../dhjf_circulation_bath.py | 48 +- .../devices/duco_gcr5/README.md | 11 + .../devices/duco_gcr5/duco_gcr5.py | 39 +- .../electrolytic_cell_gripper/README.md | 11 + .../electrolytic_cell_gripper.py | 37 ++ .../devices/hk_a0/README.md | 11 + device_package_example/devices/hk_a0/hk_a0.py | 51 ++ .../jyhsm_temperature_transmitter/README.md | 11 + .../jyhsm_temperature_transmitter.py | 42 +- .../devices/longer_bt100/README.md | 11 + .../devices/longer_bt100/longer_bt100.py | 89 +-- .../devices/runze_sy03b_t08/README.md | 11 + .../runze_sy03b_t08/runze_sy03b_t08.py | 44 +- .../devices/solenoid_valve_4v110/README.md | 11 + .../solenoid_valve_4v110.py | 48 ++ .../devices/xyz_guangdian/README.md | 11 + .../devices/xyz_guangdian/xyz_guangdian.py | 34 +- .../devices/zolix_omni_lambda/README.md | 11 + .../zolix_omni_lambda/zolix_omni_lambda.py | 32 + device_package_example/smoke_runner.py | 120 ++++ 35 files changed, 1364 insertions(+), 342 deletions(-) create mode 100644 device_package_example/SMOKE_TEST.md create mode 100644 device_package_example/smoke_runner.py diff --git a/README.md b/README.md index 377097f..6fdec74 100644 --- a/README.md +++ b/README.md @@ -69,7 +69,20 @@ class MyDevice: return self.data.get("status", "idle") ``` -### 4. 本地开发与测试 +### 4. 本地硬件冒烟(推荐第一步) + +插上硬件后,直接运行驱动文件,几秒内验证通信与控制: + +```bash +pip install pyserial # 按设备 README 安装依赖 + +cd device_package_example +python devices/hk_a0/hk_a0.py --port COM3 -v +``` + +成功时会看到 `✓ 连接成功` 和只读验证结果。完整命令列表见 [`device_package_example/SMOKE_TEST.md`](device_package_example/SMOKE_TEST.md)。 + +### 5. 本地开发与 Uni-Lab 集成 ```bash # 创建 conda 环境并安装 unilabos(需要 ROS2 完整环境) @@ -86,7 +99,7 @@ unilab --devices ./device_package_example --external_devices_only -g graph.json > **依赖自动安装**: unilabos 在启动时会自动检测 `--devices` 目录下的 `requirements.txt`,缺失的包会通过 `uv`(优先)或 `pip` 自动安装。 -### 5. CI 验证 +### 6. CI 验证 Push 代码后,GitHub Actions 会自动运行 `--check_mode` 验证你的设备定义是否正确。 diff --git a/device_package_example/SMOKE_TEST.md b/device_package_example/SMOKE_TEST.md new file mode 100644 index 0000000..f51345e --- /dev/null +++ b/device_package_example/SMOKE_TEST.md @@ -0,0 +1,97 @@ +# 本地硬件冒烟测试 + +插上硬件后,进入设备目录执行对应命令,几秒内即可看到连接与读数反馈。 + +## 通用参数 + +| 参数 | 说明 | +|------|------| +| `-v` / `--verbose` | 输出详细日志,排查串口/协议问题 | +| `--demo` | 执行低风险写操作(部分设备支持,注意安全) | +| `--port COMx` | 覆盖默认串口 | + +## 各设备命令 + +```bash +# 安装依赖(按设备 README 为准,常见为 pyserial / pymodbus) +pip install pyserial pymodbus + +# 华控模拟量输出 +python devices/hk_a0/hk_a0.py --port COM3 -v +python devices/hk_a0/hk_a0.py --port COM3 --demo # Ch1 输出 0.1V 后归零 + +# JY-HSM 温度变送器 +python devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py --port COM4 -v + +# 兰格蠕动泵 BT100-2J +python devices/longer_bt100/longer_bt100.py --port COM4 -v +python devices/longer_bt100/longer_bt100.py --port COM4 --demo # 低速运转数秒后停止 + +# Bronkhorst 流量计 +python devices/bronkhorst_el_flow/bronkhorst_el_flow.py --port COM12 -v + +# Runze SY-03B 注射泵(initialize 含归零,约 10~60 秒) +python devices/runze_sy03b_t08/runze_sy03b_t08.py --port COM4 -v + +# XYZ 光电台 +python devices/xyz_guangdian/xyz_guangdian.py --port COM35 -v + +# Duco GCR5 机械臂(网口) +python devices/duco_gcr5/duco_gcr5.py --ip 192.168.1.10 -v + +# 4V110 电磁阀 +python devices/solenoid_valve_4v110/solenoid_valve_4v110.py --port COM3 -v +python devices/solenoid_valve_4v110/solenoid_valve_4v110.py --port COM3 --demo + +# 大恒 GCI060505 光源 +python devices/daheng_gci060505/daheng_gci060505.py --port COM14 -v +python devices/daheng_gci060505/daheng_gci060505.py --port COM14 --demo + +# CNI 532nm 激光器(仅握手,不开启激光) +python devices/cni_laser_msl_u_532/cni_laser_msl_u_532.py --port COM13 -v + +# DHJF 循环浴 +python devices/dhjf_circulation_bath/dhjf_circulation_bath.py --port COM4 -v + +# CHI760E 电化学工作站(验证软件路径,不跑实验) +python devices/chi760e/chi760e.py --chi-exe-path "C:/CHI/chi760e.exe" --data-folder ./chi_data -v + +# Zolix Omni-λ 单色仪 +python devices/zolix_omni_lambda/zolix_omni_lambda.py --port COM11 -v + +# CMOS 探测器 +python devices/cmos_detector/cmos_detector.py --port COM10 -v +python devices/cmos_detector/cmos_detector.py --port COM10 --demo # 采集一帧 + +# 大恒 HD-R630c 相机(需 Galaxy SDK) +python devices/daheng_hd_r630c/daheng_hd_r630c.py -v +python devices/daheng_hd_r630c/daheng_hd_r630c.py --demo # 拍一张图 + +# 电解池夹爪 +python devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py --port COM29 -v +``` + +## 成功输出示例 + +``` +================================================== +连接设备... +✓ 连接成功 +================================================== +只读验证... + 结果: [0.0, 0.0, 0.0, 0.0, 0.0, 0.0] +✓ 只读验证完成 +✓ 已断开连接 +================================================== +冒烟测试通过 +``` + +## 与 Uni-Lab 的关系 + +| 阶段 | 命令 | 目的 | +|------|------|------| +| 1. 硬件冒烟 | `python <驱动>.py` | 确认驱动能控制本机硬件 | +| 2. Schema 校验 | `unilab --check_mode --devices ./device_package_example --external_devices_only` | CI / 注册表 | +| 3. 框架集成 | `unilab -g graph.json --backend simple` | 接入 Uni-Lab | + +冒烟脚本仅在 `python <驱动>.py` 时执行,**不影响** `import` 与 registry 扫描。 diff --git a/device_package_example/devices/bronkhorst_el_flow/README.md b/device_package_example/devices/bronkhorst_el_flow/README.md index 5effb70..af5cd9f 100644 --- a/device_package_example/devices/bronkhorst_el_flow/README.md +++ b/device_package_example/devices/bronkhorst_el_flow/README.md @@ -1,5 +1,16 @@ # Bronkhorst MFC + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python bronkhorst_el_flow.py --port COM12 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 Bronkhorst EL-FLOW Prestige 质量流量控制器(MFC)驱动,支持读取流量/温度、设置设定值与用户标签。 diff --git a/device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.py b/device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.py index 6bf1ee1..64aa39f 100644 --- a/device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.py +++ b/device_package_example/devices/bronkhorst_el_flow/bronkhorst_el_flow.py @@ -1,281 +1,323 @@ -""" -Bronkhorst EL-FLOW Prestige 质量流量控制器 (MFC) 驱动 -""" - -import logging -from typing import Dict, Any - -try: - from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode -except ImportError: - BaseROS2DeviceNode = None - -try: - import propar -except ImportError: - propar = None - -try: - from unilabos.registry.decorators import device, action, topic_config, not_action -except ImportError: - def device(**kwargs): - def wrapper(cls): - return cls - return wrapper - def action(**kwargs): - def wrapper(func): - return func - return wrapper - def topic_config(**kwargs): - def wrapper(func): - return func - return wrapper - def not_action(func): - return func - - -@device( - id="bronkhorst_el_flow", - category=["sensor", "bronkhorst_el_flow"], - description="Bronkhorst EL-FLOW Prestige 质量流量控制器", - display_name="Bronkhorst MFC", -) -class BronkhorstElFlow: - _ros_node: "BaseROS2DeviceNode" - - def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): - if device_id is None and "id" in kwargs: - device_id = kwargs.pop("id") - if config is None and "config" in kwargs: - config = kwargs.pop("config") - - self.device_id = device_id or "unknown_device" - self.config = config or {} - self.logger = logging.getLogger(f"BronkhorstElFlow.{self.device_id}") - - self.data = { - "status": "Idle", - "flow": 0.0, - "setpoint": 0.0, - "temperature": 0.0, - "valve_output": 0.0, - "capacity_unit": "", - "user_tag": "", - "level": False, - "rssi": 0, - "value": 0.0, - } - - self._port = self.config.get("port") or kwargs.get("port", "COM12") - self._baudrate = int(self.config.get("baudrate") or kwargs.get("baudrate", 38400)) - self._address = int(self.config.get("address") or kwargs.get("address", 3)) - self._channel = int(self.config.get("channel") or kwargs.get("channel", 1)) - self._threshold_pct = float(self.config.get("threshold") or kwargs.get("threshold", 2.0)) - - self._instrument = None - - @not_action - def post_init(self, ros_node: "BaseROS2DeviceNode"): - self._ros_node = ros_node - - async def _sleep(self, seconds: float): - if getattr(self, "_ros_node", None) is not None: - await self._ros_node.sleep(seconds) - else: - import time as _time - _time.sleep(seconds) - - @action(description="初始化设备") - async def initialize(self) -> bool: - self.logger.debug("initialize called, instrument=%s", self._instrument) - if self._instrument is not None: - self.data["status"] = "Idle" - self.logger.debug("设备已在 initialize 前连接") - return True - if propar is None: - self.data["status"] = "Offline" - return False - try: - self._instrument = propar.instrument( - self._port, - self._address, - baudrate=self._baudrate, - ) - unit = self._instrument.readParameter(129) - if unit is not None: - self.data["capacity_unit"] = str(unit) - tag = self._instrument.readParameter(115) - if tag is not None: - self.data["user_tag"] = str(tag) - self._poll_values() - self.data["status"] = "Idle" - self.logger.info("Bronkhorst MFC 连接成功") - return True - except Exception as e: - self.logger.error(f"连接失败: {e}") - self.data["status"] = "Offline" - return False - - @action(description="清理资源") - async def cleanup(self) -> bool: - try: - if self._instrument is not None: - try: - self._instrument.writeParameter(206, 0.0) - except Exception: - pass - self._instrument = None - self.data["status"] = "Offline" - return True - except Exception as e: - self.data["status"] = "Offline" - return False - - def _poll_values(self): - if self._instrument is None: - return - try: - flow_val = self._instrument.readParameter(205) - if flow_val is not None: - self.data["flow"] = float(flow_val) - self.data["value"] = float(flow_val) - sp_val = self._instrument.readParameter(206) - if sp_val is not None: - self.data["setpoint"] = float(sp_val) - temp_val = self._instrument.readParameter(142) - if temp_val is not None: - self.data["temperature"] = float(temp_val) - sp = self.data["setpoint"] - fl = self.data["flow"] - if sp > 0: - self.data["level"] = abs(fl - sp) / sp * 100.0 <= self._threshold_pct - else: - self.data["level"] = abs(fl) < 0.01 - except Exception as e: - self.logger.warning(f"读取设备数据失败: {e}") - - @action(description="读取流量值") - async def read_value(self, **kwargs) -> Dict[str, Any]: - self.data["status"] = "Busy" - try: - self._poll_values() - self.data["status"] = "Idle" - return { - "success": True, - "value": self.data["flow"], - "unit": self.data["capacity_unit"], - "setpoint": self.data["setpoint"], - "temperature": self.data["temperature"], - } - except Exception as e: - self.data["status"] = "Idle" - return {"success": False, "message": str(e)} - - @action(description="设置阈值百分比") - async def set_threshold(self, threshold: float, **kwargs) -> bool: - self._threshold_pct = float(threshold) - self._poll_values() - return True - - @action(description="设置流量设定值") - async def set_setpoint(self, setpoint: float, **kwargs) -> bool: - setpoint = float(setpoint) - if self._instrument is None: - self.logger.error("设备未连接") - return False - self.data["status"] = "Busy" - try: - self._instrument.writeParameter(206, setpoint) - self.data["setpoint"] = setpoint - await self._sleep(0.5) - self._poll_values() - self.data["status"] = "Idle" - return True - except Exception as e: - self.logger.error(f"set_setpoint 失败: {e}") - self.data["status"] = "Idle" - return False - - @action(description="停止流量输出") - async def stop(self, **kwargs) -> bool: - return await self.set_setpoint(0.0) - - @action(description="按百分比设置设定值") - async def set_setpoint_percent(self, percent: float, **kwargs) -> bool: - percent = float(percent) - if self._instrument is None: - return False - self.data["status"] = "Busy" - try: - raw_value = int(percent / 100.0 * 32000) - raw_value = max(0, min(32000, raw_value)) - self._instrument.setpoint = raw_value - await self._sleep(0.5) - self._poll_values() - self.data["status"] = "Idle" - return True - except Exception as e: - self.data["status"] = "Idle" - return False - - @action(description="设置用户标签") - async def set_user_tag(self, tag: str, **kwargs) -> bool: - tag = str(tag)[:12] - if self._instrument is None: - return False - try: - self._instrument.writeParameter(115, tag) - self.data["user_tag"] = tag - return True - except Exception as e: - return False - - @property - @topic_config() - def status(self) -> str: - return self.data.get("status", "Idle") - - @property - @topic_config() - def flow(self) -> float: - return self.data.get("flow", 0.0) - - @property - @topic_config() - def setpoint(self) -> float: - return self.data.get("setpoint", 0.0) - - @property - @topic_config() - def temperature(self) -> float: - return self.data.get("temperature", 0.0) - - @property - @topic_config() - def valve_output(self) -> float: - return self.data.get("valve_output", 0.0) - - @property - @topic_config() - def capacity_unit(self) -> str: - return self.data.get("capacity_unit", "") - - @property - @topic_config() - def user_tag(self) -> str: - return self.data.get("user_tag", "") - - @property - @topic_config() - def level(self) -> bool: - return self.data.get("level", False) - - @property - @topic_config() - def rssi(self) -> float: - return float(self.data.get("rssi", 0)) - - @property - @topic_config() - def value(self) -> float: - return self.data.get("value", 0.0) \ No newline at end of file +""" +Bronkhorst EL-FLOW Prestige 质量流量控制器 (MFC) 驱动 +""" + +import logging +from typing import Dict, Any + +try: + from unilabos.ros.nodes.base_device_node import BaseROS2DeviceNode +except ImportError: + BaseROS2DeviceNode = None + +try: + import propar +except ImportError: + propar = None + +try: + from unilabos.registry.decorators import device, action, topic_config, not_action +except ImportError: + def device(**kwargs): + def wrapper(cls): + return cls + return wrapper + def action(**kwargs): + def wrapper(func): + return func + return wrapper + def topic_config(**kwargs): + def wrapper(func): + return func + return wrapper + def not_action(func): + return func + + +@device( + id="bronkhorst_el_flow", + category=["sensor", "bronkhorst_el_flow"], + description="Bronkhorst EL-FLOW Prestige 质量流量控制器", + display_name="Bronkhorst MFC", +) +class BronkhorstElFlow: + _ros_node: "BaseROS2DeviceNode" + + def __init__(self, device_id: str = None, config: Dict[str, Any] = None, **kwargs): + if device_id is None and "id" in kwargs: + device_id = kwargs.pop("id") + if config is None and "config" in kwargs: + config = kwargs.pop("config") + + self.device_id = device_id or "unknown_device" + self.config = config or {} + self.logger = logging.getLogger(f"BronkhorstElFlow.{self.device_id}") + + self.data = { + "status": "Idle", + "flow": 0.0, + "setpoint": 0.0, + "temperature": 0.0, + "valve_output": 0.0, + "capacity_unit": "", + "user_tag": "", + "level": False, + "rssi": 0, + "value": 0.0, + } + + self._port = self.config.get("port") or kwargs.get("port", "COM12") + self._baudrate = int(self.config.get("baudrate") or kwargs.get("baudrate", 38400)) + self._address = int(self.config.get("address") or kwargs.get("address", 3)) + self._channel = int(self.config.get("channel") or kwargs.get("channel", 1)) + self._threshold_pct = float(self.config.get("threshold") or kwargs.get("threshold", 2.0)) + + self._instrument = None + + @not_action + def post_init(self, ros_node: "BaseROS2DeviceNode"): + self._ros_node = ros_node + + async def _sleep(self, seconds: float): + if getattr(self, "_ros_node", None) is not None: + await self._ros_node.sleep(seconds) + else: + import time as _time + _time.sleep(seconds) + + @action(description="初始化设备") + async def initialize(self) -> bool: + self.logger.debug("initialize called, instrument=%s", self._instrument) + if self._instrument is not None: + self.data["status"] = "Idle" + self.logger.debug("设备已在 initialize 前连接") + return True + if propar is None: + self.data["status"] = "Offline" + return False + try: + self._instrument = propar.instrument( + self._port, + self._address, + baudrate=self._baudrate, + ) + unit = self._instrument.readParameter(129) + if unit is not None: + self.data["capacity_unit"] = str(unit) + tag = self._instrument.readParameter(115) + if tag is not None: + self.data["user_tag"] = str(tag) + self._poll_values() + self.data["status"] = "Idle" + self.logger.info("Bronkhorst MFC 连接成功") + return True + except Exception as e: + self.logger.error(f"连接失败: {e}") + self.data["status"] = "Offline" + return False + + @action(description="清理资源") + async def cleanup(self) -> bool: + try: + if self._instrument is not None: + try: + self._instrument.writeParameter(206, 0.0) + except Exception: + pass + self._instrument = None + self.data["status"] = "Offline" + return True + except Exception as e: + self.data["status"] = "Offline" + return False + + def _poll_values(self): + if self._instrument is None: + return + try: + flow_val = self._instrument.readParameter(205) + if flow_val is not None: + self.data["flow"] = float(flow_val) + self.data["value"] = float(flow_val) + sp_val = self._instrument.readParameter(206) + if sp_val is not None: + self.data["setpoint"] = float(sp_val) + temp_val = self._instrument.readParameter(142) + if temp_val is not None: + self.data["temperature"] = float(temp_val) + sp = self.data["setpoint"] + fl = self.data["flow"] + if sp > 0: + self.data["level"] = abs(fl - sp) / sp * 100.0 <= self._threshold_pct + else: + self.data["level"] = abs(fl) < 0.01 + except Exception as e: + self.logger.warning(f"读取设备数据失败: {e}") + + @action(description="读取流量值") + async def read_value(self, **kwargs) -> Dict[str, Any]: + self.data["status"] = "Busy" + try: + self._poll_values() + self.data["status"] = "Idle" + return { + "success": True, + "value": self.data["flow"], + "unit": self.data["capacity_unit"], + "setpoint": self.data["setpoint"], + "temperature": self.data["temperature"], + } + except Exception as e: + self.data["status"] = "Idle" + return {"success": False, "message": str(e)} + + @action(description="设置阈值百分比") + async def set_threshold(self, threshold: float, **kwargs) -> bool: + self._threshold_pct = float(threshold) + self._poll_values() + return True + + @action(description="设置流量设定值") + async def set_setpoint(self, setpoint: float, **kwargs) -> bool: + setpoint = float(setpoint) + if self._instrument is None: + self.logger.error("设备未连接") + return False + self.data["status"] = "Busy" + try: + self._instrument.writeParameter(206, setpoint) + self.data["setpoint"] = setpoint + await self._sleep(0.5) + self._poll_values() + self.data["status"] = "Idle" + return True + except Exception as e: + self.logger.error(f"set_setpoint 失败: {e}") + self.data["status"] = "Idle" + return False + + @action(description="停止流量输出") + async def stop(self, **kwargs) -> bool: + return await self.set_setpoint(0.0) + + @action(description="按百分比设置设定值") + async def set_setpoint_percent(self, percent: float, **kwargs) -> bool: + percent = float(percent) + if self._instrument is None: + return False + self.data["status"] = "Busy" + try: + raw_value = int(percent / 100.0 * 32000) + raw_value = max(0, min(32000, raw_value)) + self._instrument.setpoint = raw_value + await self._sleep(0.5) + self._poll_values() + self.data["status"] = "Idle" + return True + except Exception as e: + self.data["status"] = "Idle" + return False + + @action(description="设置用户标签") + async def set_user_tag(self, tag: str, **kwargs) -> bool: + tag = str(tag)[:12] + if self._instrument is None: + return False + try: + self._instrument.writeParameter(115, tag) + self.data["user_tag"] = tag + return True + except Exception as e: + return False + + @property + @topic_config() + def status(self) -> str: + return self.data.get("status", "Idle") + + @property + @topic_config() + def flow(self) -> float: + return self.data.get("flow", 0.0) + + @property + @topic_config() + def setpoint(self) -> float: + return self.data.get("setpoint", 0.0) + + @property + @topic_config() + def temperature(self) -> float: + return self.data.get("temperature", 0.0) + + @property + @topic_config() + def valve_output(self) -> float: + return self.data.get("valve_output", 0.0) + + @property + @topic_config() + def capacity_unit(self) -> str: + return self.data.get("capacity_unit", "") + + @property + @topic_config() + def user_tag(self) -> str: + return self.data.get("user_tag", "") + + @property + @topic_config() + def level(self) -> bool: + return self.data.get("level", False) + + @property + @topic_config() + def rssi(self) -> float: + return float(self.data.get("rssi", 0)) + + @property + @topic_config() + def value(self) -> float: + return self.data.get("value", 0.0) + + +# ========== 本地硬件冒烟========== +# python bronkhorst_el_flow.py --port COM12 [-v] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="Bronkhorst EL-FLOW - 本地硬件冒烟") + add_serial_args(parser, default_port="COM12", default_baudrate=38400) + parser.add_argument("--address", type=int, default=3) + parser.add_argument("--channel", type=int, default=1) + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = BronkhorstElFlow( + device_id="smoke_test", + config={ + "port": args.port, + "baudrate": args.baudrate, + "address": args.address, + "channel": args.channel, + }, + ) + return await smoke_lifecycle( + dev, + read_fn=lambda d: d.read_value(), + ) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() \ No newline at end of file diff --git a/device_package_example/devices/chi760e/README.md b/device_package_example/devices/chi760e/README.md index 98fe727..bf204f4 100644 --- a/device_package_example/devices/chi760e/README.md +++ b/device_package_example/devices/chi760e/README.md @@ -1,5 +1,16 @@ # CHI760E 电化学工作站 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python chi760e.py --chi-exe-path "C:/CHI/chi760e.exe" --data-folder ./chi_data -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 辰华 CHI760E 电化学工作站驱动,通过 CHI 软件宏命令(`.mcr`)控制,支持 CV / LSV / CA / OCP / NPV / EIS 等实验。 diff --git a/device_package_example/devices/chi760e/chi760e.py b/device_package_example/devices/chi760e/chi760e.py index a19d607..294a9da 100644 --- a/device_package_example/devices/chi760e/chi760e.py +++ b/device_package_example/devices/chi760e/chi760e.py @@ -773,3 +773,48 @@ def last_experiment_time(self) -> str: def data_folder(self) -> str: """数据保存目录""" return self.data.get("data_folder", "") + + +# ========== 本地硬件冒烟========== +# python chi760e.py --chi-exe-path "C:/CHI/chi760e.exe" --data-folder ./chi_data [-v] +# 验证 CHI 软件路径与数据目录(不启动电化学实验) + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="CHI760E 电化学工作站 - 本地硬件冒烟") + parser.add_argument("--chi-exe-path", default="", dest="chi_exe_path", help="CHI 软件路径") + parser.add_argument("--data-folder", default="./chi_data", dest="data_folder", help="数据目录") + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = CHI760E( + device_id="smoke_test", + config={ + "chi_exe_path": args.chi_exe_path, + "data_folder": args.data_folder, + }, + ) + + def read_state(d): + return { + "status": d.status, + "data_folder": d.data_folder, + "chi_exe_path": d._chi_exe_path, + } + + return await smoke_lifecycle(dev, read_fn=read_state) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() diff --git a/device_package_example/devices/cmos_detector/README.md b/device_package_example/devices/cmos_detector/README.md index f05cd7d..e45ab5a 100644 --- a/device_package_example/devices/cmos_detector/README.md +++ b/device_package_example/devices/cmos_detector/README.md @@ -1,5 +1,16 @@ # CMOS 线阵检测器 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python cmos_detector.py --port COM10 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 LCAMV8 CMOS 线阵检测器(S11639-01,2048 像素)驱动,支持积分时间、增益、单帧/连续采集及波长矫正。 diff --git a/device_package_example/devices/cmos_detector/cmos_detector.py b/device_package_example/devices/cmos_detector/cmos_detector.py index bb68515..d9963f6 100644 --- a/device_package_example/devices/cmos_detector/cmos_detector.py +++ b/device_package_example/devices/cmos_detector/cmos_detector.py @@ -808,3 +808,44 @@ async def save_data_to_file(self, filename: str = "") -> str: except Exception as e: self.logger.error(f"保存失败: {e}") return f"save failed: {e}" + + +# ========== 本地硬件冒烟========== +# python cmos_detector.py --port COM10 [-v] [--demo] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="CMOS 探测器 - 本地硬件冒烟") + add_serial_args(parser, default_port="COM10", default_baudrate=115200) + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = CMOSDetector( + device_id="smoke_test", + config={"port": args.port, "baudrate": args.baudrate}, + ) + + async def demo(d): + return await d.read_frame() + + return await smoke_lifecycle( + dev, + read_fn=lambda d: {"status": d.status, "pixel_count": getattr(d, "PIXEL_COUNT", "unknown")}, + demo_fn=demo, + do_demo=args.demo, + ) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() diff --git a/device_package_example/devices/cni_laser_msl_u_532/README.md b/device_package_example/devices/cni_laser_msl_u_532/README.md index e79eef5..fafbfa0 100644 --- a/device_package_example/devices/cni_laser_msl_u_532/README.md +++ b/device_package_example/devices/cni_laser_msl_u_532/README.md @@ -1,5 +1,16 @@ # CNI 532nm 激光器 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python cni_laser_msl_u_532.py --port COM13 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 CNI MSL-U-532-50mW 激光器驱动,通过 Arduino Nano + MCP4725 DAC 控制功率,串口发送 `SET 0-100` 指令。 diff --git a/device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.py b/device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.py index 66c84c2..ae45b58 100644 --- a/device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.py +++ b/device_package_example/devices/cni_laser_msl_u_532/cni_laser_msl_u_532.py @@ -280,3 +280,45 @@ async def cleanup(self) -> bool: self.data["power"] = 0.0 self.data["power_percentage"] = 0.0 return True + + +# ========== 本地硬件冒烟========== +# python cni_laser_msl_u_532.py --port COM13 [-v] +# 注意:仅验证串口通信与固件握手,不会开启激光 + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="CNI 532nm 激光器 - 本地硬件冒烟") + add_serial_args(parser, default_port="COM13", default_baudrate=9600) + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = CNILaserMSLU532( + device_id="smoke_test", + config={"port": args.port, "baudrate": args.baudrate}, + ) + + def read_state(d): + return { + "status": d.status, + "laser_on": d.laser_on, + "power": d.power, + "wavelength": d.wavelength, + } + + return await smoke_lifecycle(dev, read_fn=read_state) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() diff --git a/device_package_example/devices/daheng_gci060505/README.md b/device_package_example/devices/daheng_gci060505/README.md index d57bcbb..9c5b18d 100644 --- a/device_package_example/devices/daheng_gci060505/README.md +++ b/device_package_example/devices/daheng_gci060505/README.md @@ -1,5 +1,16 @@ # GCI-060505 LED 光源 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python daheng_gci060505.py --port COM14 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 大恒 GCI-060505 LED 光源驱动,通过 Arduino + MCP4725 DAC 控制亮度,支持 PING/ON/OFF/BRIGHT/STATUS 指令。 diff --git a/device_package_example/devices/daheng_gci060505/daheng_gci060505.py b/device_package_example/devices/daheng_gci060505/daheng_gci060505.py index dbdf7e3..507ce43 100644 --- a/device_package_example/devices/daheng_gci060505/daheng_gci060505.py +++ b/device_package_example/devices/daheng_gci060505/daheng_gci060505.py @@ -217,3 +217,53 @@ async def set_brightness(self, brightness: float) -> bool: async def refresh_status(self) -> bool: self._refresh_from_arduino() return True + + +# ========== 本地硬件冒烟========== +# python daheng_gci060505.py --port COM14 [-v] [--demo] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="大恒 GCI060505 光源 - 本地硬件冒烟") + add_serial_args(parser, default_port="COM14", default_baudrate=115200) + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = DahengGCI060505( + device_id="smoke_test", + config={"port": args.port, "baudrate": args.baudrate}, + ) + + async def read_state(d): + await d.refresh_status() + return { + "status": d.status, + "light_on": d.light_on, + "brightness": d.brightness, + } + + async def demo(d): + await d.set_brightness(10.0) + await d.turn_off() + + return await smoke_lifecycle( + dev, + read_fn=read_state, + demo_fn=demo, + do_demo=args.demo, + ) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() diff --git a/device_package_example/devices/daheng_hd_r630c/README.md b/device_package_example/devices/daheng_hd_r630c/README.md index 22a287f..5c3a7b9 100644 --- a/device_package_example/devices/daheng_hd_r630c/README.md +++ b/device_package_example/devices/daheng_hd_r630c/README.md @@ -1,5 +1,16 @@ # HD-R630C 工业相机 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python daheng_hd_r630c.py -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 实验室设备铭牌为 **大恒 HD-R630C-U3** USB3.0 彩色工业相机;据现场开发人员说明,该机本质为度申科技生产、大恒光电贴牌销售,**接入时使用度申 DVP 开发包**(GenTL)。本驱动基于 Harvesters + GenICam(USB3 Vision)接口,默认加载度申 `DVPCameraTL64.cti`。 diff --git a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py index 0354c9c..50132f0 100644 --- a/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py +++ b/device_package_example/devices/daheng_hd_r630c/daheng_hd_r630c.py @@ -510,3 +510,53 @@ def get_last_image(self) -> Optional[np.ndarray]: numpy.ndarray or None: BGR 格式图像数据 """ return self._last_image + + +# ========== 本地硬件冒烟========== +# python daheng_hd_r630c.py [--device-index 0] [-v] [--demo] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="大恒 HD-R630c 相机 - 本地硬件冒烟") + parser.add_argument("--device-index", type=int, default=0, dest="device_index") + parser.add_argument("--cti-path", default="", dest="cti_path", help="度申 DVP GenTL 路径(可选)") + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + config = {"device_index": args.device_index} + if args.cti_path: + config["cti_path"] = args.cti_path + dev = DahengHdR630c(device_id="smoke_test", config=config) + + def read_state(d): + return { + "status": d.status, + "is_streaming": d.is_streaming, + "image_width": d.image_width, + "image_height": d.image_height, + } + + async def demo(d): + return await d.snap() + + return await smoke_lifecycle( + dev, + read_fn=read_state, + demo_fn=demo, + do_demo=args.demo, + ) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() diff --git a/device_package_example/devices/dhjf_circulation_bath/README.md b/device_package_example/devices/dhjf_circulation_bath/README.md index ae7885e..e3ff256 100644 --- a/device_package_example/devices/dhjf_circulation_bath/README.md +++ b/device_package_example/devices/dhjf_circulation_bath/README.md @@ -1,5 +1,16 @@ # DHJF 循环水浴 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python dhjf_circulation_bath.py --port COM4 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 DHJF-2005A 低温恒温搅拌反应浴驱动,Modbus RTU 通信,支持温度设定、搅拌控制与多段程序。 diff --git a/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.py b/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.py index ac7c09a..c117a11 100644 --- a/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.py +++ b/device_package_example/devices/dhjf_circulation_bath/dhjf_circulation_bath.py @@ -476,4 +476,50 @@ async def program(self, segments: List[Tuple[float, int, int]]) -> bool: for i, triplet in enumerate(segments, start=1): t, h, m = float(triplet[0]), int(triplet[1]), int(triplet[2]) ok &= await self.set_segment(i, t, h, m) - return ok \ No newline at end of file + return ok + + +# ========== 本地硬件冒烟========== +# python dhjf_circulation_bath.py --port COM4 [-v] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="DHJF 循环浴 - 本地硬件冒烟") + add_serial_args(parser, default_port="COM4", default_baudrate=9600) + parser.add_argument("--slave-id", type=int, default=1, dest="slave_id") + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = DHJFCirculationBath( + device_id="smoke_test", + config={ + "port": args.port, + "baudrate": args.baudrate, + "slave_id": args.slave_id, + }, + ) + + def read_state(d): + return { + "temp": d.temp, + "temp_target": d.temp_target, + "stir_speed": d.stir_speed, + "status": d.status, + } + + return await smoke_lifecycle(dev, read_fn=read_state) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() \ No newline at end of file diff --git a/device_package_example/devices/duco_gcr5/README.md b/device_package_example/devices/duco_gcr5/README.md index b5be810..999bbe3 100644 --- a/device_package_example/devices/duco_gcr5/README.md +++ b/device_package_example/devices/duco_gcr5/README.md @@ -1,5 +1,16 @@ # DUCO 协作机器人 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python duco_gcr5.py --ip 192.168.1.10 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 新松 DUCO GCR5-910 协作机器人驱动,TCP 2000 端口纯文本协议,支持上电、使能、运行程序与速度调节。 diff --git a/device_package_example/devices/duco_gcr5/duco_gcr5.py b/device_package_example/devices/duco_gcr5/duco_gcr5.py index 8e22335..9062b72 100644 --- a/device_package_example/devices/duco_gcr5/duco_gcr5.py +++ b/device_package_example/devices/duco_gcr5/duco_gcr5.py @@ -481,4 +481,41 @@ async def clear_error(self) -> str: self.data["error_message"] = "" return "clear success" else: - return f"clear fail: {resp or 'no response'}" \ No newline at end of file + return f"clear fail: {resp or 'no response'}" + + +# ========== 本地硬件冒烟========== +# python duco_gcr5.py --ip 192.168.1.10 [-v] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_ip_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="Duco GCR5 机械臂 - 本地硬件冒烟") + add_ip_args(parser, default_ip="192.168.1.10", default_port=2000) + parser.add_argument("--status-port", type=int, default=2001, dest="status_port") + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = DucoGCR5( + device_id="smoke_test", + config={ + "ip": args.ip, + "cmd_port": args.cmd_port, + "status_port": args.status_port, + }, + ) + return await smoke_lifecycle(dev, read_fn=lambda d: d.query_state()) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() \ No newline at end of file diff --git a/device_package_example/devices/electrolytic_cell_gripper/README.md b/device_package_example/devices/electrolytic_cell_gripper/README.md index f73e6fb..9de4bdf 100644 --- a/device_package_example/devices/electrolytic_cell_gripper/README.md +++ b/device_package_example/devices/electrolytic_cell_gripper/README.md @@ -1,5 +1,16 @@ # 电解池夹爪 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python electrolytic_cell_gripper.py --port COM29 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 电解池夹爪工作站驱动,整合 2 台**俏优灵**步进电机(水平/垂直)与 1 台**大寰** PGE 平行电爪。 diff --git a/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py b/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py index fec2b59..7ea51f1 100644 --- a/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py +++ b/device_package_example/devices/electrolytic_cell_gripper/electrolytic_cell_gripper.py @@ -763,3 +763,40 @@ async def emergency_stop(self): time_module.sleep(0.02) self._motor_emergency_stop(self._motor2_id) self.data["status"] = "Stopped" + + +# ========== 本地硬件冒烟========== +# python electrolytic_cell_gripper.py --port COM29 [-v] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="电解池夹爪 - 本地硬件冒烟") + add_serial_args(parser, default_port="COM29", default_baudrate=115200) + parser.add_argument("--motor", type=int, default=1, help="读取位置的电机编号 (1 或 2)") + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = ElectrolyticCellGripper( + device_id="smoke_test", + config={"port": args.port, "baudrate": args.baudrate}, + ) + motor = args.motor + return await smoke_lifecycle( + dev, + read_fn=lambda d: d.read_motor_position(motor), + ) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() diff --git a/device_package_example/devices/hk_a0/README.md b/device_package_example/devices/hk_a0/README.md index e773e80..3f6cce5 100644 --- a/device_package_example/devices/hk_a0/README.md +++ b/device_package_example/devices/hk_a0/README.md @@ -1,5 +1,16 @@ # 华控模拟量输出 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python hk_a0.py --port COM3 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 华控电子(惠州)**模拟量输出**模块驱动,RS485 Modbus RTU,通过功能码 **06/10** 写保持寄存器设定各通道电压/电流输出。 diff --git a/device_package_example/devices/hk_a0/hk_a0.py b/device_package_example/devices/hk_a0/hk_a0.py index 61ad620..096d9c1 100644 --- a/device_package_example/devices/hk_a0/hk_a0.py +++ b/device_package_example/devices/hk_a0/hk_a0.py @@ -228,3 +228,54 @@ def status(self) -> str: @topic_config() def outputs(self) -> List[float]: return self.data.get("outputs", [0.0] * self.channel_count) + + +# ========== 本地硬件冒烟========== +# python hk_a0.py --port COM3 [-v] [--demo] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="华控模拟量输出 - 本地硬件冒烟") + add_serial_args(parser, default_port="/dev/ttyUSB0", default_baudrate=9600) + parser.add_argument("--slave-address", type=int, default=1, dest="slave_address") + parser.add_argument("--channel-count", type=int, default=6, dest="channel_count") + parser.add_argument("--output-max", type=float, default=5.0, dest="output_max") + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = HKA0( + device_id="smoke_test", + config={ + "port": args.port, + "baudrate": args.baudrate, + "slave_address": args.slave_address, + "channel_count": args.channel_count, + "output_max": args.output_max, + }, + ) + + async def demo(dev_): + await dev_.set_output(1, 0.1) + await dev_.stop_all() + + return await smoke_lifecycle( + dev, + read_fn=lambda d: d.read_outputs(), + demo_fn=demo, + do_demo=args.demo, + ) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() diff --git a/device_package_example/devices/jyhsm_temperature_transmitter/README.md b/device_package_example/devices/jyhsm_temperature_transmitter/README.md index 32fd5fc..e998a3a 100644 --- a/device_package_example/devices/jyhsm_temperature_transmitter/README.md +++ b/device_package_example/devices/jyhsm_temperature_transmitter/README.md @@ -1,5 +1,16 @@ # JY-HSM 温度变送器 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python jyhsm_temperature_transmitter.py --port COM4 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 安徽久跃 JY-HSM 一体化温度变送器驱动,Modbus RTU 读取实时温度,支持阈值监控与提醒。 diff --git a/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py index b8f2cdb..90da628 100644 --- a/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py +++ b/device_package_example/devices/jyhsm_temperature_transmitter/jyhsm_temperature_transmitter.py @@ -663,4 +663,44 @@ async def set_baudrate(self, baudrate: float) -> bool: return True except Exception: self.data["status"] = "Error" - return False \ No newline at end of file + return False + + +# ========== 本地硬件冒烟========== +# python jyhsm_temperature_transmitter.py --port COM4 [-v] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="JY-HSM 温度变送器 - 本地硬件冒烟") + add_serial_args(parser, default_port="COM4", default_baudrate=9600) + parser.add_argument("--slave-address", type=int, default=1, dest="slave_address") + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = JyhsmTemperatureTransmitter( + device_id="smoke_test", + config={ + "port": args.port, + "baudrate": args.baudrate, + "slave_address": args.slave_address, + }, + ) + return await smoke_lifecycle( + dev, + read_fn=lambda d: d.read_temperature(), + ) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() \ No newline at end of file diff --git a/device_package_example/devices/longer_bt100/README.md b/device_package_example/devices/longer_bt100/README.md index c8d53b8..462603b 100644 --- a/device_package_example/devices/longer_bt100/README.md +++ b/device_package_example/devices/longer_bt100/README.md @@ -1,5 +1,16 @@ # 兰格蠕动泵 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python longer_bt100.py --port COM4 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 兰格 BT100-2J 蠕动泵驱动,WJ/RJ ASCII 协议,RS485 通信,支持转速、方向与启停控制。 diff --git a/device_package_example/devices/longer_bt100/longer_bt100.py b/device_package_example/devices/longer_bt100/longer_bt100.py index e17f721..fa5931d 100644 --- a/device_package_example/devices/longer_bt100/longer_bt100.py +++ b/device_package_example/devices/longer_bt100/longer_bt100.py @@ -540,71 +540,52 @@ def is_fullspeed(self) -> bool: return self.data.get("is_fullspeed", False) -# ========== 独立测试入口 ========== +# ========== 本地硬件冒烟========== +# python longer_bt100.py --port COM4 [-v] [--demo] -def _main(): + +def _smoke_main(): import argparse import asyncio + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle - parser = argparse.ArgumentParser( - description="单独测试兰格 BT100-2J 驱动" - ) - parser.add_argument("--port", default="COM4", help="串口,如 COM4 或 /dev/ttyUSB0") - parser.add_argument("--baudrate", type=int, default=1200) + parser = argparse.ArgumentParser(description="兰格 BT100-2J 蠕动泵 - 本地硬件冒烟") + add_serial_args(parser, default_port="COM4", default_baudrate=1200) parser.add_argument("--address", type=int, default=1) - parser.add_argument("--device-id", default="test_bt100", dest="device_id") - parser.add_argument("-v", "--verbose", action="store_true") - parser.add_argument( - "--demo-run", - action="store_true", - help="执行短时 run→sleep→stop 演示(注意安全)" - ) + add_common_args(parser) parser.add_argument("--demo-speed", type=float, default=50.0, dest="demo_speed") parser.add_argument("--demo-direction", choices=("CW", "CCW"), default="CW", dest="demo_direction") parser.add_argument("--demo-seconds", type=float, default=3.0, dest="demo_seconds") args = parser.parse_args() - - logging.basicConfig( - level=logging.DEBUG if args.verbose else logging.INFO, - format="%(asctime)s [%(levelname)s] %(name)s: %(message)s", - ) + setup_logging(args.verbose) async def run(): - config = { - "port": args.port, - "baudrate": args.baudrate, - "address": args.address, - } - pump = LongerBT100(device_id=args.device_id, config=config) - if not await pump.initialize(): - return 1 - try: - print("=" * 50) - print("读取泵状态...") - st = await pump.read_status() - print(f"read_status: {st}") - print(f"pump.data: {pump.data}") - - if args.demo_run: - print("=" * 50) - print(f"演示: 设置转速 {args.demo_speed} RPM, 方向 {args.demo_direction}") - await pump.set_speed(args.demo_speed) - await pump.set_direction(args.demo_direction) - print("启动泵...") - await pump.start() - print(f"运行 {args.demo_seconds} 秒...") - await asyncio.sleep(args.demo_seconds) - print("停止泵...") - await pump.stop() - st2 = await pump.read_status() - print(f"演示后状态: {st2}") - finally: - await pump.cleanup() - return 0 - - sys.exit(asyncio.run(run())) + dev = LongerBT100( + device_id="smoke_test", + config={"port": args.port, "baudrate": args.baudrate, "address": args.address}, + ) + + async def demo(d): + await d.set_speed(args.demo_speed) + await d.set_direction(args.demo_direction) + await d.start() + await asyncio.sleep(args.demo_seconds) + await d.stop() + return await d.read_status() + + return await smoke_lifecycle( + dev, + read_fn=lambda d: d.read_status(), + demo_fn=demo, + do_demo=args.demo, + ) + + run_smoke(run) if __name__ == "__main__": - import sys - _main() \ No newline at end of file + _smoke_main() \ No newline at end of file diff --git a/device_package_example/devices/runze_sy03b_t08/README.md b/device_package_example/devices/runze_sy03b_t08/README.md index 9376d8d..cf2a63c 100644 --- a/device_package_example/devices/runze_sy03b_t08/README.md +++ b/device_package_example/devices/runze_sy03b_t08/README.md @@ -1,5 +1,16 @@ # 润泽注射泵 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python runze_sy03b_t08.py --port COM4 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 润泽 SY-03B 陶瓷注射泵(T-08 八通分配阀)驱动,ASCII DT 格式 RS232/RS485 通信,25 mL 注射器。 diff --git a/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py b/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py index 7901a89..608acc7 100644 --- a/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py +++ b/device_package_example/devices/runze_sy03b_t08/runze_sy03b_t08.py @@ -404,4 +404,46 @@ def is_closed(self) -> bool: return False -DEVICE_CLASS = RunzeSY03BT08 \ No newline at end of file +DEVICE_CLASS = RunzeSY03BT08 + + +# ========== 本地硬件冒烟========== +# python runze_sy03b_t08.py --port COM4 [-v] +# 注意:initialize 会执行泵复位归零,耗时约 10~60 秒 + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="Runze SY-03B 注射泵 - 本地硬件冒烟") + add_serial_args(parser, default_port="COM4", default_baudrate=9600) + parser.add_argument("--address", type=int, default=0) + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = RunzeSY03BT08( + device_id="smoke_test", + config={"port": args.port, "baudrate": args.baudrate, "address": args.address}, + ) + + def read_state(d): + return { + "status": d.status, + "position": d.position, + "valve_position": d.valve_position, + } + + return await smoke_lifecycle(dev, read_fn=read_state) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() \ No newline at end of file diff --git a/device_package_example/devices/solenoid_valve_4v110/README.md b/device_package_example/devices/solenoid_valve_4v110/README.md index d9f76fa..7cffe03 100644 --- a/device_package_example/devices/solenoid_valve_4v110/README.md +++ b/device_package_example/devices/solenoid_valve_4v110/README.md @@ -1,5 +1,16 @@ # 4V110 电磁阀 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python solenoid_valve_4v110.py --port COM3 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 亚德客 4V110-06 DC24V 二位五通电磁阀驱动,通过 Arduino Uno GPIO + 继电器模块控制 24 V 线圈。 diff --git a/device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.py b/device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.py index ba0a023..19ed563 100644 --- a/device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.py +++ b/device_package_example/devices/solenoid_valve_4v110/solenoid_valve_4v110.py @@ -232,3 +232,51 @@ def status(self) -> str: @topic_config() def valve_position(self) -> str: return self.data.get("valve_position", "Closed") + + +# ========== 本地硬件冒烟========== +# python solenoid_valve_4v110.py --port COM3 [-v] [--demo] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="4V110 电磁阀 - 本地硬件冒烟") + add_serial_args(parser, default_port="COM3", default_baudrate=9600) + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = SolenoidValve4V110( + device_id="smoke_test", + config={"port": args.port, "baudrate": args.baudrate}, + ) + + async def read_state(d): + return { + "is_closed": await d.is_closed(), + "valve_position": d.valve_position, + } + + async def demo(dev_): + await dev_.open() + await dev_.close() + + return await smoke_lifecycle( + dev, + read_fn=read_state, + demo_fn=demo, + do_demo=args.demo, + ) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() diff --git a/device_package_example/devices/xyz_guangdian/README.md b/device_package_example/devices/xyz_guangdian/README.md index 5d7a422..17f7b35 100644 --- a/device_package_example/devices/xyz_guangdian/README.md +++ b/device_package_example/devices/xyz_guangdian/README.md @@ -1,5 +1,16 @@ # XYZ 三维平台 + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python xyz_guangdian.py --port COM35 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 XYZ 光电工作台驱动,控制三轴运动平台与推杆装置,Modbus RTU 通信,支持绝对/相对移动与推杆夹紧/释放。 diff --git a/device_package_example/devices/xyz_guangdian/xyz_guangdian.py b/device_package_example/devices/xyz_guangdian/xyz_guangdian.py index fb24ad7..92201bb 100644 --- a/device_package_example/devices/xyz_guangdian/xyz_guangdian.py +++ b/device_package_example/devices/xyz_guangdian/xyz_guangdian.py @@ -709,4 +709,36 @@ async def set_acceleration(self, axis: str, accel: float) -> bool: except Exception as e: self.logger.error(f"设置加速度失败: {e}") - return False \ No newline at end of file + return False + + +# ========== 本地硬件冒烟========== +# python xyz_guangdian.py --port COM35 [-v] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="XYZ 光电台 - 本地硬件冒烟") + add_serial_args(parser, default_port="COM35", default_baudrate=9600) + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = XYZGuangdian( + device_id="smoke_test", + config={"port": args.port, "baudrate": args.baudrate}, + ) + return await smoke_lifecycle(dev, read_fn=lambda d: d.get_position()) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() \ No newline at end of file diff --git a/device_package_example/devices/zolix_omni_lambda/README.md b/device_package_example/devices/zolix_omni_lambda/README.md index c7645dd..666bfdc 100644 --- a/device_package_example/devices/zolix_omni_lambda/README.md +++ b/device_package_example/devices/zolix_omni_lambda/README.md @@ -1,5 +1,16 @@ # Zolix Omni-λ + +## 本地快速验证 + +插上硬件后,在设备目录执行: + +```bash +python zolix_omni_lambda.py --port COM11 -v +``` + +加 `-v` 查看详细日志;部分设备支持 `--demo` 做低风险写操作验证。完整说明见 [SMOKE_TEST.md](../../SMOKE_TEST.md)。 + ## 简介 Zolix Omni-λ 单色仪/光谱仪驱动,串口 ASCII 指令控制波长/波数移动、光栅切换与出入口选择。 diff --git a/device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.py b/device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.py index 8ccb3aa..de7ee87 100644 --- a/device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.py +++ b/device_package_example/devices/zolix_omni_lambda/zolix_omni_lambda.py @@ -660,3 +660,35 @@ def entrance_port(self) -> str: def system_info(self) -> str: """仪器系统信息""" return str(self.data.get("system_info", "")) + + +# ========== 本地硬件冒烟========== +# python zolix_omni_lambda.py --port COM11 [-v] + + +def _smoke_main(): + import argparse + import sys + from pathlib import Path + + sys.path.insert(0, str(Path(__file__).resolve().parents[2])) + from smoke_runner import add_common_args, add_serial_args, run_smoke, setup_logging, smoke_lifecycle + + parser = argparse.ArgumentParser(description="Zolix Omni-λ 单色仪 - 本地硬件冒烟") + add_serial_args(parser, default_port="COM11", default_baudrate=19200) + add_common_args(parser) + args = parser.parse_args() + setup_logging(args.verbose) + + async def run(): + dev = ZolixOmniLambda( + device_id="smoke_test", + config={"port": args.port, "baudrate": args.baudrate}, + ) + return await smoke_lifecycle(dev, read_fn=lambda d: d.query_system_info()) + + run_smoke(run) + + +if __name__ == "__main__": + _smoke_main() diff --git a/device_package_example/smoke_runner.py b/device_package_example/smoke_runner.py new file mode 100644 index 0000000..7861972 --- /dev/null +++ b/device_package_example/smoke_runner.py @@ -0,0 +1,120 @@ +""" +本地硬件冒烟测试通用工具。 + +各设备驱动底部的 ``if __name__ == "__main__"`` 块使用本模块; +仅在 ``python .py`` 时加载,不影响 import 与 registry 扫描。 +""" + +from __future__ import annotations + +import argparse +import asyncio +import inspect +import logging +import sys +from pathlib import Path +from typing import Any, Awaitable, Callable, Optional, Union + +AsyncMainFn = Callable[[], Awaitable[int]] + + +def setup_smoke_path() -> None: + """将 device_package_example 加入 sys.path,便于各驱动 import 本模块。""" + pkg_root = Path(__file__).resolve().parent + root_str = str(pkg_root) + if root_str not in sys.path: + sys.path.insert(0, root_str) + + +def setup_logging(verbose: bool = False) -> None: + logging.basicConfig( + level=logging.DEBUG if verbose else logging.INFO, + format="%(asctime)s [%(levelname)s] %(name)s: %(message)s", + ) + + +def section(title: str) -> None: + print("=" * 50) + print(title) + + +def ok(msg: str) -> None: + print(f"✓ {msg}") + + +def fail(msg: str) -> None: + print(f"✗ {msg}") + + +def add_common_args(parser: argparse.ArgumentParser) -> None: + parser.add_argument("-v", "--verbose", action="store_true", help="输出详细日志") + parser.add_argument( + "--demo", + action="store_true", + help="执行低风险 demo 写操作(注意安全)", + ) + + +def add_serial_args( + parser: argparse.ArgumentParser, + *, + default_port: str = "COM4", + default_baudrate: int = 9600, +) -> None: + parser.add_argument("--port", default=default_port, help="串口号") + parser.add_argument("--baudrate", type=int, default=default_baudrate, help="波特率") + + +def add_ip_args( + parser: argparse.ArgumentParser, + *, + default_ip: str = "192.168.1.10", + default_port: int = 2000, +) -> None: + parser.add_argument("--ip", default=default_ip, help="设备 IP") + parser.add_argument("--cmd-port", type=int, default=default_port, dest="cmd_port", help="命令端口") + + +async def _maybe_await(value: Any) -> Any: + if inspect.isawaitable(value): + return await value + return value + + +async def smoke_lifecycle( + dev: Any, + *, + read_fn: Optional[Callable[[Any], Union[Any, Awaitable[Any]]]] = None, + demo_fn: Optional[Callable[[Any], Union[Any, Awaitable[Any]]]] = None, + do_demo: bool = False, +) -> int: + """标准冒烟流程:initialize → 只读验证 → 可选 demo → cleanup。""" + section("连接设备...") + init_ok = await _maybe_await(dev.initialize()) + if not init_ok: + fail("initialize 失败") + return 1 + ok("连接成功") + + try: + if read_fn is not None: + section("只读验证...") + result = await _maybe_await(read_fn(dev)) + print(f" 结果: {result}") + ok("只读验证完成") + + if do_demo and demo_fn is not None: + section("Demo 操作(--demo)...") + result = await _maybe_await(demo_fn(dev)) + print(f" 结果: {result}") + ok("Demo 完成") + finally: + await _maybe_await(dev.cleanup()) + ok("已断开连接") + + section("冒烟测试通过") + return 0 + + +def run_smoke(main_fn: AsyncMainFn) -> None: + sys.exit(asyncio.run(main_fn()))