From a2fd2daff13ffe2473d6fcf4492593312a9f018b Mon Sep 17 00:00:00 2001 From: Havoc <2993167370@qq.com> Date: Sat, 31 May 2025 22:38:35 +0800 Subject: [PATCH] =?UTF-8?q?=E5=9C=A8=E5=9B=BE=E5=83=8F=E5=A4=84=E7=90=86?= =?UTF-8?q?=E5=99=A8=E4=B8=AD=E5=BC=95=E5=85=A5=E6=97=A5=E5=BF=97=E8=AE=B0?= =?UTF-8?q?=E5=BD=95=E5=8A=9F=E8=83=BD=EF=BC=8C=E6=9B=BF=E6=8D=A2=E4=BA=86?= =?UTF-8?q?=E5=A4=9A=E4=B8=AA=E6=89=93=E5=8D=B0=E8=AF=AD=E5=8F=A5=E4=B8=BA?= =?UTF-8?q?=E6=97=A5=E5=BF=97=E8=AE=B0=E5=BD=95=EF=BC=8C=E5=A2=9E=E5=BC=BA?= =?UTF-8?q?=E4=BA=86=E9=94=99=E8=AF=AF=E5=92=8C=E7=8A=B6=E6=80=81=E4=BF=A1?= =?UTF-8?q?=E6=81=AF=E7=9A=84=E5=8F=AF=E8=BF=BD=E8=B8=AA=E6=80=A7=E3=80=82?= =?UTF-8?q?=E8=B0=83=E6=95=B4=E4=BA=86=E5=BC=82=E6=AD=A5=E6=89=AB=E6=8F=8F?= =?UTF-8?q?=E7=9A=84=E5=90=AF=E5=8A=A8=E5=92=8C=E5=81=9C=E6=AD=A2=E9=80=BB?= =?UTF-8?q?=E8=BE=91=EF=BC=8C=E7=A1=AE=E4=BF=9D=E6=9B=B4=E5=A5=BD=E7=9A=84?= =?UTF-8?q?=E9=94=99=E8=AF=AF=E5=A4=84=E7=90=86=E5=92=8C=E4=BF=A1=E6=81=AF?= =?UTF-8?q?=E5=8F=8D=E9=A6=88=E3=80=82?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- utils/image_raw.py | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/utils/image_raw.py b/utils/image_raw.py index 448d984..baa90dd 100644 --- a/utils/image_raw.py +++ b/utils/image_raw.py @@ -10,6 +10,7 @@ from qreader import QReader from threading import Thread, Lock import time import queue +from utils.log_helper import get_logger class ImageSubscriber(Node): @@ -47,6 +48,7 @@ class ImageProcessor: self.qreader = QReader() self.spin_thread = None self.running = True + self.log = get_logger("图像处理器") # 异步 QR 码扫描相关 self.scan_thread = None @@ -66,7 +68,7 @@ class ImageProcessor: while self.running: rclpy.spin_once(self.image_subscriber, timeout_sec=0.1) except Exception as e: - print(f"Spin thread error: {e}") + self.log.error(f"Spin线程错误: {e}", "错误") def destroy(self): self.running = False @@ -94,7 +96,7 @@ class ImageProcessor: interval: 扫描间隔,单位秒 """ if self.scan_thread is not None and self.scan_thread.is_alive(): - print("异步扫描已经在运行中") + self.log.warning("异步扫描已经在运行中", "警告") return self.enable_async_scan = True @@ -102,14 +104,14 @@ class ImageProcessor: self.scan_thread = Thread(target=self._async_scan_worker, args=(interval,)) self.scan_thread.daemon = True # 设为守护线程,主线程结束时自动结束 self.scan_thread.start() - print("启动异步 QR 码扫描线程") + self.log.info("启动异步 QR 码扫描线程", "启动") def stop_async_scan(self): """停止异步 QR 码扫描""" self.enable_async_scan = False if self.scan_thread and self.scan_thread.is_alive(): self.scan_thread.join(timeout=1.0) - print("异步 QR 码扫描线程已停止") + self.log.info("异步 QR 码扫描线程已停止", "停止") def _async_scan_worker(self, interval): """异步扫描工作线程""" @@ -131,10 +133,10 @@ class ImageProcessor: if qr_data: self.last_qr_result = qr_data self.last_qr_time = current_time - print(f"异步扫描到 QR 码: {qr_data}") + self.log.success(f"异步扫描到 QR 码: {qr_data}", "扫描") except Exception as e: self.is_scanning = False - print(f"异步 QR 码扫描出错: {e}") + self.log.error(f"异步 QR 码扫描出错: {e}", "错误") last_scan_time = current_time