From 5e14311103cdf05646479d51adcc7e982fae8b65 Mon Sep 17 00:00:00 2001 From: havocrao Date: Wed, 20 Aug 2025 00:18:02 +0800 Subject: [PATCH] =?UTF-8?q?feat:=20qrcode=20=E9=BB=98=E8=AE=A4=E9=87=87?= =?UTF-8?q?=E7=94=A8=20ai=20=E7=9B=B8=E6=9C=BA?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- utils/image_raw.py | 22 ++++++++-------------- 1 file changed, 8 insertions(+), 14 deletions(-) diff --git a/utils/image_raw.py b/utils/image_raw.py index 134d373..a75fefd 100755 --- a/utils/image_raw.py +++ b/utils/image_raw.py @@ -57,7 +57,6 @@ class ImageSubscriber(Node): self.image_sub_ai= self.create_subscription( Image, '/image', self.image_callback_ai, 10 ) - # 工具初始化 self.bridge = CvBridge() @@ -144,7 +143,6 @@ class ImageSubscriber(Node): self.get_logger().error(f"保存{prefix}图像失败: {str(e)}") return False - def image_callback_rgb(self, msg): # """安全的图像回调""" # if getattr(self, '_shutdown_flag', False): @@ -162,9 +160,6 @@ class ImageSubscriber(Node): except Exception as e: self.get_logger().error(f"RGB图像处理错误: {str(e)}") - - - def image_callback_left(self, msg): try: self.cv_image_left = self.bridge.imgmsg_to_cv2(msg, 'bgr8') @@ -192,7 +187,6 @@ class ImageSubscriber(Node): except Exception as e: self.get_logger().error(f"ai图像处理错误: {str(e)}") - def safe_spin(self): """安全spin循环""" while rclpy.ok() and not getattr(self, '_shutdown_flag', False): @@ -251,7 +245,7 @@ class ImageProcessor: self.image_subscriber.stop_camera() self.image_subscriber.destroy_node() - def get_current_image(self,text): + def get_current_image(self, text): if text=='ai': return self.image_subscriber.cv_image_ai if text=='left': @@ -265,7 +259,7 @@ class ImageProcessor: def decode_all_qrcodes(self, img=None): """使用pyzbar解码QR码""" if img is None: - img = self.get_current_image() + img = self.get_current_image('ai') if img is None: return None @@ -317,7 +311,7 @@ class ImageProcessor: interval: 扫描间隔,单位秒 """ if self.scan_thread is not None and self.scan_thread.is_alive(): - # self.log.warning("异步扫描已经在运行中", "警告") + self.log.warning("异步扫描已经在运行中", "警告") print('scan,warn') return @@ -326,7 +320,7 @@ class ImageProcessor: self.scan_thread = Thread(target=self._async_scan_worker, args=(interval,)) self.scan_thread.daemon = True # 设为守护线程,主线程结束时自动结束 self.scan_thread.start() - # self.log.info("启动异步 QR 码扫描线程", "启动") + self.log.info("启动异步 QR 码扫描线程", "启动") print('start') def stop_async_scan(self): @@ -334,7 +328,7 @@ class ImageProcessor: self.enable_async_scan = False if self.scan_thread and self.scan_thread.is_alive(): self.scan_thread.join(timeout=1.0) - # self.log.info("异步 QR 码扫描线程已停止", "停止") + self.log.info("异步 QR 码扫描线程已停止", "停止") print('stop') def _async_scan_worker(self, interval): @@ -346,7 +340,7 @@ class ImageProcessor: # 按指定间隔扫描 if current_time - last_scan_time >= interval: - img = self.get_current_image() + img = self.get_current_image('ai') if img is not None: try: self.is_scanning = True @@ -358,11 +352,11 @@ class ImageProcessor: if qr_data: self.last_qr_result = qr_data self.last_qr_time = current_time - # self.log.success(f"异步扫描到 QR 码: {qr_data}", "扫描") + self.log.success(f"异步扫描到 QR 码: {qr_data}", "扫描") print(f"异步扫描到 QR 码: {qr_data}") except Exception as e: self.is_scanning = False - # self.log.error(f"异步 QR 码扫描出错: {e}", "错误") + self.log.error(f"异步 QR 码扫描出错: {e}", "错误") print(f"异步 QR 码扫描出错: {e}") else: print('no img')