update power estimation and upload 2 models of yolo
This commit is contained in:
5
app.yaml
5
app.yaml
@@ -16,12 +16,17 @@ files:
|
|||||||
- laser_manager.py
|
- laser_manager.py
|
||||||
- logger_manager.py
|
- logger_manager.py
|
||||||
- main.py
|
- main.py
|
||||||
|
- model_270139.cvimodel
|
||||||
|
- model_270139.mud
|
||||||
|
- model_270820.cvimodel
|
||||||
|
- model_270820.mud
|
||||||
- network.py
|
- network.py
|
||||||
- ota_manager.py
|
- ota_manager.py
|
||||||
- power.py
|
- power.py
|
||||||
- server.pem
|
- server.pem
|
||||||
- shoot_manager.py
|
- shoot_manager.py
|
||||||
- shot_id_generator.py
|
- shot_id_generator.py
|
||||||
|
- target_roi_yolo.py
|
||||||
- time_sync.py
|
- time_sync.py
|
||||||
- triangle_positions.json
|
- triangle_positions.json
|
||||||
- triangle_target.py
|
- triangle_target.py
|
||||||
|
|||||||
148
config.py
148
config.py
@@ -18,7 +18,7 @@ CAMERA_HEIGHT = 480
|
|||||||
|
|
||||||
# 三角形检测缩图比例:默认按相机最长边缩到 1/2(性能更稳;可按需调整)
|
# 三角形检测缩图比例:默认按相机最长边缩到 1/2(性能更稳;可按需调整)
|
||||||
# 取值范围建议 (0.25 ~ 1.0];1.0 表示不缩图
|
# 取值范围建议 (0.25 ~ 1.0];1.0 表示不缩图
|
||||||
TRIANGLE_DETECT_SCALE = 0.5
|
TRIANGLE_DETECT_SCALE = 0.4
|
||||||
|
|
||||||
# ==================== 服务器配置 ====================
|
# ==================== 服务器配置 ====================
|
||||||
# SERVER_IP = "stcp.shelingxingqiu.com"
|
# SERVER_IP = "stcp.shelingxingqiu.com"
|
||||||
@@ -138,6 +138,11 @@ CAMERA_CALIB_XML = APP_DIR + "/cameraParameters.xml"
|
|||||||
TRIANGLE_POSITIONS_JSON = APP_DIR + "/triangle_positions.json"
|
TRIANGLE_POSITIONS_JSON = APP_DIR + "/triangle_positions.json"
|
||||||
# 检测到的三角形边长在图像中的像素范围,分辨率或靶纸占比变化时可微调
|
# 检测到的三角形边长在图像中的像素范围,分辨率或靶纸占比变化时可微调
|
||||||
TRIANGLE_SIZE_RANGE = (8, 500)
|
TRIANGLE_SIZE_RANGE = (8, 500)
|
||||||
|
# PnP 距离合理性检查(可选):超出范围时认为本次检测有误,回退圆心算法
|
||||||
|
# 设为 0 表示不启用(主要防线是单应矩阵 sx/sy 比值检查,无需提前知道距离)
|
||||||
|
# 如果射箭距离很固定,可设具体范围(如 min=2.5, max=6.0)作为额外保险
|
||||||
|
TRIANGLE_DISTANCE_MIN_M = 0.0 # 0=不启用下限检查
|
||||||
|
TRIANGLE_DISTANCE_MAX_M = 0.0 # 0=不启用上限检查
|
||||||
# 三角形检测兜底增强:CLAHE(更鲁棒但更慢)。颜色阈值修复后通常不需要,保持关闭以优先速度。
|
# 三角形检测兜底增强:CLAHE(更鲁棒但更慢)。颜色阈值修复后通常不需要,保持关闭以优先速度。
|
||||||
TRIANGLE_ENABLE_CLAHE_FALLBACK = False
|
TRIANGLE_ENABLE_CLAHE_FALLBACK = False
|
||||||
# 三角形检测调试:保存 Otsu 二值化图像(临时调试用,定位后关闭)
|
# 三角形检测调试:保存 Otsu 二值化图像(临时调试用,定位后关闭)
|
||||||
@@ -152,18 +157,144 @@ TRIANGLE_DARK_PIXEL_GRAY = 130
|
|||||||
TRIANGLE_MIN_DARK_RATIO = 0.30
|
TRIANGLE_MIN_DARK_RATIO = 0.30
|
||||||
# 三角形相对对比度阈值:内部比周围暗多少灰度值才认为有效(0=禁用相对对比度)
|
# 三角形相对对比度阈值:内部比周围暗多少灰度值才认为有效(0=禁用相对对比度)
|
||||||
TRIANGLE_MIN_CONTRAST_DIFF = 15
|
TRIANGLE_MIN_CONTRAST_DIFF = 15
|
||||||
# 三角形检测超时(毫秒)。超过该时间直接判失败,回退圆心算法(并行时不再等待)。
|
# 三角形形状约束容差(等腰直角判定松紧度)
|
||||||
# CLAHE 启用或颜色阈值放宽后检测耗时增加,需相应提高(1000→2500)
|
# 增大可容忍轮廓轻微变形(印刷不均、阴影局部切角),减少"差一点点就失败"的漏检
|
||||||
TRIANGLE_TIMEOUT_MS = 2500
|
# 建议范围:0.20(原始/严格) ~ 0.30(宽松);超过 0.35 容易误检非三角形
|
||||||
|
TRIANGLE_SHAPE_LEG_TOLERANCE = 0.25 # 两直角边长度比例容差(原 0.20)
|
||||||
|
TRIANGLE_SHAPE_HYP_TOLERANCE = 0.25 # 斜边与期望长度比例容差(原 0.20)
|
||||||
|
TRIANGLE_SHAPE_COS_TOLERANCE = 0.25 # 直角余弦绝对值上限(原 0.20,越小越严格)
|
||||||
|
# 三角形检测主超时(毫秒):join 等待子线程的最长时间。
|
||||||
|
# 整段 try_triangle_scoring 含「多路径二值化 + C(n,4) 四角评分 + 单应性 + PnP」,往往比黄心圆检测慢。
|
||||||
|
# 建议设为实测最坏耗时的 1.2 倍;超时后圆心检测仍会并行跑完,跑完后若三角形已结束则优先用三角形。
|
||||||
|
TRIANGLE_TIMEOUT_MS = 1500
|
||||||
|
# True=打印各阶段耗时(ms),用于定位瓶颈;稳定后可 False 减少日志
|
||||||
|
TRIANGLE_TIMING_LOG = True
|
||||||
|
# True=Stage2 每个子框内传统三角失败时打一条统计(Otsu/Adaptive 下轮廓数与各拒绝原因计数)
|
||||||
|
TRIANGLE_LOG_STAGE2_PATCH_REJECT = True
|
||||||
|
|
||||||
|
# 仅检出 3 个真实三角时:是否在预测位置附近做小 ROI(Otsu/adaptive)再搜第 4 个真实三角。
|
||||||
|
# False=跳过该搜索,直接用几何推算的虚拟第 4 点(offset_method=triangle_homography_3pt),省 ~10~120ms;若实测偏移可接受可关。
|
||||||
|
TRIANGLE_FOURTH_ROI_SEARCH_ENABLE = False
|
||||||
|
|
||||||
|
# ── 轻量锐化(Unsharp Mask)──────────────────────────────────────────────────
|
||||||
|
# 目的:轻度/中度模糊时增强边缘,让三角形轮廓更易被 approxPolyDP 检出。
|
||||||
|
# 严重运动模糊时反而会放大噪声,建议搭配 sharpness 检测自动触发(见下)。
|
||||||
|
# YOLO 裁切后图已较清晰时可 False,省去 Unsharp 开销并减轻振铃。
|
||||||
|
TRIANGLE_SHARPEN_ENABLE = False # False=关闭锐化(彻底跳过计算,最省时)
|
||||||
|
# 仅当帧清晰度(Laplacian 方差)低于此值时才锐化;高于此值说明图片本身够清晰,不动
|
||||||
|
# 0=总是锐化;建议 50~150;对应日志中 [TRI] sharpness=xxx
|
||||||
|
TRIANGLE_SHARPEN_THRESHOLD = 0.0 # 0=总是锐化(不做 Laplacian 判断,省去计算)
|
||||||
|
# Unsharp Mask 高斯核 sigma(越大锐化越强,通常 1.0~3.0)
|
||||||
|
TRIANGLE_SHARPEN_SIGMA = 2.0
|
||||||
|
# Unsharp Mask 强度系数(越大锐化越猛,通常 1.2~2.0;>2 易产生振铃)
|
||||||
|
TRIANGLE_SHARPEN_STRENGTH = 1.5
|
||||||
|
|
||||||
|
# 三角形检测用灰度来源(ROI 裁切、缩放到 img_det 之后;与 vision 一致按 RGB 输入)
|
||||||
|
# rgb — 常规 cv2.cvtColor RGB2GRAY
|
||||||
|
# v_suppress — HSV 的 V:亮度 >= TRIANGLE_HSV_V_SUPPRESS_ABOVE 的像素灰度强制为 255,压制黄/红/蓝等亮环后再走原有 Otsu 流水线
|
||||||
|
# fallback_v_suppress — 先用 rgb 跑 detect;若检出三角形 <3,再用 v_suppress 重跑一遍(省平均耗时,坏帧可多救一点)
|
||||||
|
# try_both — rgb 与 v_suppress 各完整跑一遍 detect_triangle_markers,取检出数更多一侧(平局保留 rgb);耗时约 2 倍,用于对比效果
|
||||||
|
TRIANGLE_GRAY_MODE = "v_suppress"
|
||||||
|
TRIANGLE_HSV_V_SUPPRESS_ABOVE = 200 # 0~255;偏高则环残留多,偏低则可能伤到暗三角边缘,建议 180~220 扫一圈
|
||||||
|
|
||||||
# 三角形检测性能/鲁棒性参数(偏向速度的默认值)
|
# 三角形检测性能/鲁棒性参数(偏向速度的默认值)
|
||||||
# 说明:
|
# 说明:
|
||||||
# - Otsu 是最快的全局阈值;adaptiveThreshold 更鲁棒但更慢
|
# - Otsu 是最快的全局阈值;adaptiveThreshold 更鲁棒但更慢
|
||||||
# - filtered 候选过多时,枚举 C(n,4) 会变慢,需限幅
|
# - filtered 候选过多时,枚举 C(n,4) 会变慢,需限幅
|
||||||
TRIANGLE_EARLY_EXIT_CANDIDATES = 4 # 找到多少个候选就提前停止二值化尝试
|
TRIANGLE_EARLY_EXIT_CANDIDATES = 3 # 找到3个候选即停(第4个由几何推算);原来4需跑完全adaptive
|
||||||
TRIANGLE_ADAPTIVE_BLOCK_SIZES = (11, 21) # 自适应阈值 blockSize 尝试列表;置空 () 可完全关闭 adaptiveThreshold
|
TRIANGLE_ADAPTIVE_BLOCK_SIZES = (11,) # 只用1个block_size;原(11,21)跑两遍adaptive
|
||||||
TRIANGLE_MAX_FILTERED_FOR_COMBO = 10 # 参与四点组合评分的最大候选数(超过则截断到最可能的一部分)
|
TRIANGLE_MAX_FILTERED_FOR_COMBO = 10 # 参与四点组合评分的最大候选数(超过则截断到最可能的一部分)
|
||||||
|
|
||||||
|
# ROI 局部阈值:四个象限各自 Otsu(+ 可选 ROI 内 adaptive),再合并候选。
|
||||||
|
# 顺序:紧接在全局 Otsu 之后、整图 adaptive 之前(见 triangle_target.detect_triangle_markers)。
|
||||||
|
# 用途:阴阳脸/大阴影下往往比「先整图 adaptive」更省时间且更稳;整图 adaptive 最慢,作补充。
|
||||||
|
#
|
||||||
|
# YOLO 已裁到靶区时,整幅小图上单一全局 Otsu 容易把环与四角揉在一个阈值里;可跳过第一轮「全局轮廓提取」,
|
||||||
|
# 直接进入下面四象限 ROI Otsu(仍会算全局 b_otsu 供 relaxed approxPolyDP 回退)。整图模式勿开。
|
||||||
|
TRIANGLE_SKIP_GLOBAL_OTSU_EXTRACT_ON_YOLO_ROI = True
|
||||||
|
|
||||||
|
TRIANGLE_ROI_ENABLED = False
|
||||||
|
TRIANGLE_ROI_MIN_CANDIDATES = 3 # 候选数低于此值时启用 ROI 局部阈值(需至少 3 个点才能三角解算)
|
||||||
|
TRIANGLE_ROI_OVERLAP_RATIO = 0.08 # 象限 ROI 的重叠比例(避免角标落在分割边界被切断)
|
||||||
|
TRIANGLE_ROI_USE_ADAPTIVE = False # ROI 内关闭 adaptive(只跑ROI Otsu,省去4×adaptive);遇到阴阳脸再开
|
||||||
|
|
||||||
|
# 多路径融合:不同二值化路径若得到相近中心(dedup 格点),累加 path_votes,后续优先参与四点组合。
|
||||||
|
TRIANGLE_MULTI_PATH_VOTE = True
|
||||||
|
|
||||||
|
# 失败回退(仍不足 TRIANGLE_FALLBACK_MIN_CANDIDATES 时按序尝试,每条仅在前序仍不足时执行)
|
||||||
|
TRIANGLE_FALLBACK_MIN_CANDIDATES = 3
|
||||||
|
# 对同一幅 Otsu 二值图用更宽松的 approxPolyDP,找回被“切角”的轮廓
|
||||||
|
TRIANGLE_FALLBACK_RELAXED_EPS = True
|
||||||
|
TRIANGLE_RELAXED_POLY_EPS_SCALE = 1.65
|
||||||
|
# Black-hat(顶帽逆):突出比周围暗的斑块,再 Otsu;对阴影/照度不均往往有效,略慢于纯 Otsu
|
||||||
|
TRIANGLE_FALLBACK_BLACKHAT = True
|
||||||
|
TRIANGLE_BLACKHAT_KERNEL_FRAC = 0.018 # 核大小 ≈ min(h,w)*frac,取奇数,范围约 [7, 31]
|
||||||
|
|
||||||
|
# ── YOLO(NPU) 靶环 ROI → 裁剪后再跑三角形(减小 CPU 处理面积)──────────────────
|
||||||
|
# 日志里 net_in=W×H 来自 .mud 模型(det.input_width/height),不是这里配置的。
|
||||||
|
TRIANGLE_YOLO_ROI_ENABLE = True
|
||||||
|
TRIANGLE_YOLO_MODEL_PATH = APP_DIR + "/model_270139.mud"
|
||||||
|
# 参与 ROI 的类别:多类时只填「整靶/靶环」的 id;不要填角标类,否则 union 仍可对,但 largest 会偏小。
|
||||||
|
TRIANGLE_YOLO_RING_CLASS_IDS = (0,)
|
||||||
|
TRIANGLE_YOLO_CONF_TH = 0.7
|
||||||
|
TRIANGLE_YOLO_IOU_TH = 0.45
|
||||||
|
# YOLO 首次/临界帧可能在高阈值下 0 框;启用后仅在 0 候选时用较低阈值重试一次。
|
||||||
|
# 后续仍会经过 min_box_side、ROI aspect、三角形几何校验,避免直接放大假阳性。
|
||||||
|
TRIANGLE_YOLO_RETRY_ON_EMPTY = True
|
||||||
|
TRIANGLE_YOLO_RETRY_CONF_TH = 0.5
|
||||||
|
TRIANGLE_YOLO_ROI_MARGIN_FRAC = 0.11
|
||||||
|
# union: 所有候选框外接矩形(一类多框:环+四角);largest: 只取面积最大的框
|
||||||
|
TRIANGLE_YOLO_ROI_MERGE_MODE = "union"
|
||||||
|
# native: Maix 已将框映射到相机分辨率;letterbox: 框在网络输入坐标需逆变换(重复映射会出细条 ROI)
|
||||||
|
TRIANGLE_YOLO_COORD_MODE = "native"
|
||||||
|
# 参与 ROI 合并前丢弃过小的框(低 conf 时边角 1×1 假阳性)
|
||||||
|
TRIANGLE_YOLO_MIN_BOX_SIDE_PX = 8
|
||||||
|
TRIANGLE_YOLO_REJECT_BAD_ROI = True
|
||||||
|
# try_triangle_scoring 收到 ROI 后裁剪的最小边长(像素),过小则退回整图
|
||||||
|
TRIANGLE_CROP_ROI_MIN_SIDE_PX = 64
|
||||||
|
# 射箭保存图 / 预览上绘制 YOLO 靶环 ROI 矩形 (x0,y0,x1,y1),核对是否裁准;不需要时改 False
|
||||||
|
TRIANGLE_YOLO_DRAW_ROI_ON_SHOT = True
|
||||||
|
# 开机阶段预加载 YOLO detector;detect 使用 dual_buff=False,避免返回上一帧结果。
|
||||||
|
TRIANGLE_YOLO_PRELOAD_ON_BOOT = True
|
||||||
|
|
||||||
|
# ── 第二段 YOLO:仅在 Stage1 裁切出的靶环图上推理(与合成 stage2 训练数据一致)→ 子框内传统算法取直角点 ──
|
||||||
|
# Stage1 靶环裁切内如何找黑三角标记(对比耗时时可切换):
|
||||||
|
# "yolo" — 调 Stage2 黑三角模型得子框,再子框内传统提取(需 TRIANGLE_BLACK_YOLO_ENABLE=True)。
|
||||||
|
# "traditional" — 不调 Stage2 模型;仅在 Stage1 ROI 整幅上跑传统 detect_triangle_markers(与 yolo 路径对比用)。
|
||||||
|
TRIANGLE_BLACK_TRIANGLE_LOCATE_MODE = "traditional"
|
||||||
|
# True 时每箭另打一枪端到端耗时:yolo_ring + yolo_black + try_triangle_scoring 墙钟(毫秒)
|
||||||
|
TRIANGLE_LOG_E2E_TIMING = True
|
||||||
|
TRIANGLE_BLACK_YOLO_ENABLE = True
|
||||||
|
TRIANGLE_BLACK_YOLO_MODEL_PATH = APP_DIR + "/model_270820.mud"
|
||||||
|
TRIANGLE_BLACK_YOLO_CLASS_IDS = (0,)
|
||||||
|
TRIANGLE_BLACK_YOLO_CONF_TH = 0.5
|
||||||
|
TRIANGLE_BLACK_YOLO_IOU_TH = 0.45
|
||||||
|
# Maix YOLOv5 detect 返回的框已映射到传入的 Stage1 裁切图坐标;contain/letterbox 是模型内部预处理。
|
||||||
|
TRIANGLE_BLACK_YOLO_COORD_MODE = "native"
|
||||||
|
# 子框相对 YOLO 框的扩展(在靶环裁切图坐标系下),利于传统算法取边
|
||||||
|
TRIANGLE_BLACK_YOLO_BOX_MARGIN_FRAC = 0.08
|
||||||
|
TRIANGLE_BLACK_YOLO_MIN_BOX_SIDE_PX = 6.0
|
||||||
|
# 子框传统检测不足 3 个时是否回退为「整幅靶环 ROI」上的原 detect_triangle_markers
|
||||||
|
TRIANGLE_BLACK_YOLO_FALLBACK_ON_PATCH_FAIL = True
|
||||||
|
# Stage2 子框内传统提取使用的灰度(有缩略时默认在 Stage1 全分辨率灰度上切片):
|
||||||
|
# "rgb" — 仅用 RGB→灰度(不再做 Unsharp、不做 V 抑制),最省 CPU(推荐子框已对准黑三角时)。
|
||||||
|
# "global" — 与整幅 ROI 三角流程同一张 gray(含 TRIANGLE_GRAY_MODE 的 v_suppress 与锐化);更稳但更耗时。
|
||||||
|
TRIANGLE_BLACK_YOLO_PATCH_GRAY_SOURCE = "rgb"
|
||||||
|
# Stage2 子框内轮廓→三角形:approxPolyDP 的 ε=周长×FRAC×mult。边模糊时略增大 FRAC 或保留多级 mult。
|
||||||
|
TRIANGLE_PATCH_APPROXPOLY_FRAC = 0.055
|
||||||
|
TRIANGLE_PATCH_APPROXPOLY_RELAX_MULTS = (1.0, 1.3, 1.65)
|
||||||
|
# Otsu/Adaptive 前对子框灰度轻模糊:0=关闭;3 或 5=Gaussian ksize(须为奇数),压锯齿利于收成 3 顶点
|
||||||
|
TRIANGLE_PATCH_PRE_BLUR_KSIZE = 0
|
||||||
|
TRIANGLE_BLACK_YOLO_PRELOAD_ON_BOOT = True
|
||||||
|
# 每箭是否在日志中打印黑三角 detect 统计(raw/类过滤/是否在环内);调通后可 False 减日志
|
||||||
|
TRIANGLE_BLACK_YOLO_LOG_EACH_SHOT = True
|
||||||
|
# True=每次射箭将 Stage1 裁切图(黑三角模型输入)存为 JPEG;调试用,量产请 False
|
||||||
|
TRIANGLE_BLACK_YOLO_SAVE_ROI_CROP = True
|
||||||
|
# 存盘目录;空字符串表示使用 PHOTO_DIR + "/stage2_roi"
|
||||||
|
TRIANGLE_BLACK_YOLO_ROI_CROP_DIR = ""
|
||||||
|
# 存盘 JPEG 上绘制 Stage2(黑三角 YOLO)最终子框(绿框 + s2_0… 标签)
|
||||||
|
TRIANGLE_BLACK_YOLO_SAVE_ROI_DRAW_BOXES = True
|
||||||
|
|
||||||
FLASH_LASER_WHILE_SHOOTING = False # 是否在拍摄时闪一下激光(True=闪,False=不闪)
|
FLASH_LASER_WHILE_SHOOTING = False # 是否在拍摄时闪一下激光(True=闪,False=不闪)
|
||||||
FLASH_LASER_DURATION_MS = 1000 # 闪一下激光的持续时间(毫秒)
|
FLASH_LASER_DURATION_MS = 1000 # 闪一下激光的持续时间(毫秒)
|
||||||
|
|
||||||
@@ -176,6 +307,8 @@ LASER_LENGTH = 2
|
|||||||
SAVE_IMAGE_ENABLED = True # 是否保存图像(True=保存,False=不保存)
|
SAVE_IMAGE_ENABLED = True # 是否保存图像(True=保存,False=不保存)
|
||||||
PHOTO_DIR = "/root/phot" # 照片存储目录
|
PHOTO_DIR = "/root/phot" # 照片存储目录
|
||||||
MAX_IMAGES = 1000
|
MAX_IMAGES = 1000
|
||||||
|
# Stage2 调试目录(默认 PHOTO_DIR/stage2_roi)内 JPEG 最多保留张数;None 表示与 MAX_IMAGES 相同
|
||||||
|
TRIANGLE_BLACK_YOLO_STAGE2_ROI_MAX_IMAGES = None
|
||||||
|
|
||||||
SHOW_CAMERA_PHOTO_WHILE_SHOOTING = False # 是否在拍摄时显示摄像头图像(True=显示,False=不显示),建议在连着USB测试过程中打开
|
SHOW_CAMERA_PHOTO_WHILE_SHOOTING = False # 是否在拍摄时显示摄像头图像(True=显示,False=不显示),建议在连着USB测试过程中打开
|
||||||
|
|
||||||
@@ -198,3 +331,6 @@ PIN_MAPPINGS = {
|
|||||||
# ==================== 电源配置 ====================
|
# ==================== 电源配置 ====================
|
||||||
AUTO_POWER_OFF_IN_SECONDS = 10 * 60 # 自动关机时间(秒),0表示不自动关机
|
AUTO_POWER_OFF_IN_SECONDS = 10 * 60 # 自动关机时间(秒),0表示不自动关机
|
||||||
|
|
||||||
|
BATTERY_SOC_LPF_ALPHA = 0.5
|
||||||
|
BATTERY_SOC_AVG_WINDOW = 5
|
||||||
|
|
||||||
|
|||||||
184
design_doc/algo.md
Normal file
184
design_doc/algo.md
Normal file
@@ -0,0 +1,184 @@
|
|||||||
|
1. 系统目标
|
||||||
|
# 检测靶纸四角的等腰直角三角形标记(每个角一个)
|
||||||
|
# 计算激光落点在靶面上的二维偏移(厘米)
|
||||||
|
# 通过PnP算法估算靶面到相机的距离(米)
|
||||||
|
|
||||||
|
2. 核心算法流程
|
||||||
|
2.1 三角形检测 (detect_triangle_markers)
|
||||||
|
采用多策略级联保证鲁棒性:
|
||||||
|
图像输入 → 多阈值策略 → 候选三角形过滤 → 四点匹配
|
||||||
|
检测策略(按优先级):
|
||||||
|
|
||||||
|
1.全局Otsu二值化(最快,~10ms)
|
||||||
|
2.自适应阈值(多种block size,光照不均时)
|
||||||
|
3.ROI局部阈值(候选不足3个时,分象限独立处理)
|
||||||
|
4.Black-Hat形态学增强(仍不足时,突出暗色标记)
|
||||||
|
|
||||||
|
三角形几何验证:
|
||||||
|
# 必须是直角三角形(检查勾股定理,容差20%)
|
||||||
|
# 两直角边长度差<20%
|
||||||
|
# 内部像素足够暗(灰度≤130,暗像素比例≥30%)
|
||||||
|
# 与周围背景对比度≥15灰度级
|
||||||
|
|
||||||
|
四点匹配算法:
|
||||||
|
# 从候选三角形中枚举所有4点组合
|
||||||
|
# 计算四边形评分:(对角比-1)*3 + (水平比-1) + (垂直比-1) + (边长偏差)*2
|
||||||
|
# 选择评分最低的组合作为四角标记
|
||||||
|
|
||||||
|
2.2 单应性落点计算 (homography_calibration)
|
||||||
|
建立图像坐标系 → 靶面坐标系(二维平面)的透视变换
|
||||||
|
|
||||||
|
将激光点像素坐标映射到靶面坐标(厘米)
|
||||||
|
|
||||||
|
使用RANSAC提高鲁棒性(阈值1像素)
|
||||||
|
|
||||||
|
2.3 PnP距离估计 (pnp_distance_meters)
|
||||||
|
已知四个标记点的三维坐标(x,y,z,单位cm)
|
||||||
|
|
||||||
|
通过solvePnP求解相机外参(旋转+平移)
|
||||||
|
|
||||||
|
距离 = ‖平移向量‖ / 100(转换为米)
|
||||||
|
|
||||||
|
3. 关键优化策略
|
||||||
|
3.1 多路径投票
|
||||||
|
同一图像区域被不同二值化方法检测到时,path_votes++
|
||||||
|
|
||||||
|
选择投票数高的候选,提高检测可信度
|
||||||
|
|
||||||
|
3.2 早退机制
|
||||||
|
候选≥3个 且 覆盖3个以上象限 → 停止更多阈值尝试
|
||||||
|
|
||||||
|
大幅降低嵌入式设备计算开销
|
||||||
|
|
||||||
|
3.3 3点补全机制
|
||||||
|
当只检测到3个角时,通过仿射变换估算第4个角位置
|
||||||
|
|
||||||
|
公式:P_missing = M_inv @ [x_target, y_target, 1]
|
||||||
|
|
||||||
|
3.4 图像缩放
|
||||||
|
默认缩放到0.5倍进行检测(由config控制)
|
||||||
|
|
||||||
|
坐标还原时乘以inv_scale,保持与标定矩阵一致
|
||||||
|
|
||||||
|
4. 数据流示例
|
||||||
|
python
|
||||||
|
输入:
|
||||||
|
- img_rgb: H×W×3 图像
|
||||||
|
- laser_xy: (x_px, y_px) 激光点像素坐标
|
||||||
|
- marker_positions: {0:[0,0,0], 1:[0,30,0], 2:[30,30,0], 3:[30,0,0]} # 4角3D坐标(cm)
|
||||||
|
|
||||||
|
输出:
|
||||||
|
{
|
||||||
|
"ok": True,
|
||||||
|
"dx_cm": 2.5, # 靶面X偏移(cm,向右为正)
|
||||||
|
"dy_cm": -3.2, # 靶面Y偏移(cm,向上为正)
|
||||||
|
"distance_m": 5.43, # 相机到靶面距离(米)
|
||||||
|
"offset_method": "triangle_homography",
|
||||||
|
"distance_method": "pnp_triangle"
|
||||||
|
}
|
||||||
|
5. 鲁棒性设计
|
||||||
|
5.1 参数自适应
|
||||||
|
从config.py动态读取所有阈值(可在线调整)
|
||||||
|
|
||||||
|
三角形边长范围、灰度阈值、对比度要求等均可配置
|
||||||
|
|
||||||
|
5.2 异常处理
|
||||||
|
角点退化检测(距离<3像素判定为重复)
|
||||||
|
|
||||||
|
NaN/Inf校验(单应性矩阵、偏移量、距离)
|
||||||
|
|
||||||
|
距离合理性检查(0.3~20米)
|
||||||
|
|
||||||
|
5.3 降级策略
|
||||||
|
PnP失败 → 只输出偏移,距离置None
|
||||||
|
|
||||||
|
4角检测失败 → 尝试3角补全
|
||||||
|
|
||||||
|
快速路径失败 → CLAHE增强兜底(可选)
|
||||||
|
|
||||||
|
6. 性能特点
|
||||||
|
CPU友好:默认Otsu单次处理,多数场景10-30ms完成检测
|
||||||
|
|
||||||
|
内存可控:最大候选数截断(默认10个),避免组合爆炸
|
||||||
|
|
||||||
|
嵌入式适配:支持图像缩放、早退机制降低计算量
|
||||||
|
|
||||||
|
7. 局限性
|
||||||
|
依赖四个等腰直角三角形(需靶纸特殊设计)
|
||||||
|
|
||||||
|
要求三角形内部足够暗、与背景有对比度
|
||||||
|
|
||||||
|
单应性假设靶面为平面(实际靶纸可能有轻微起伏)
|
||||||
|
|
||||||
|
这套算法在射击训练系统中作为主要定位手段。
|
||||||
|
|
||||||
|
8. 为了加速单应性的计算,引入了yolo模型,一共做了两个模型,一个为靶纸和黑色三角形一体的识别模型,用于做原照片上快速找到靶纸区域。另一个模型是黑色三角形的模型,用于做靶纸区域再找黑色三角形。但是经过对比发现,引入黑色三角形模型反而更慢。入下面的流程A和流程B:
|
||||||
|
yolo靶纸+传统(流程B) yolo靶纸+yolo黑色三角形(流程A)
|
||||||
|
平均值 646.08 916.4457143
|
||||||
|
标准差 94.61300968 57.40401849
|
||||||
|
|
||||||
|
公共前置(两条路都一样)
|
||||||
|
是否用靶环模型裁 Stage1
|
||||||
|
|
||||||
|
TRIANGLE_YOLO_ROI_ENABLE=True 时:跑 靶环 YOLO,得到全图上的 roi_xyxy,后面的三角形都在 img_work = 全图[roi] 上做(必要时再缩成 img_det 给整图传统分支用)。
|
||||||
|
False 时:roi_xyxy=None,三角形在 整幅相机图 上当 img_work。
|
||||||
|
之后都进入 try_triangle_scoring(img_cv, …, roi_xyxy=…, black_yolo_boxes_work=…)
|
||||||
|
|
||||||
|
在里面先做灰度、v_suppress、锐化、det_scale 缩略图等 prep(与是否黑三角模型无关)。
|
||||||
|
差别从 black_yolo_boxes_work 有没有有效子框列表 开始。
|
||||||
|
|
||||||
|
流程 A:用黑色三角形模型(Stage2 黑三角 YOLO)
|
||||||
|
配置要点:TRIANGLE_BLACK_YOLO_ENABLE=True,且 TRIANGLE_BLACK_TRIANGLE_LOCATE_MODE="yolo",并且 已有 Stage1 裁切(roi_xyxy 不能为 None,否则根本不会跑黑三角 YOLO)。
|
||||||
|
|
||||||
|
步骤概要:
|
||||||
|
|
||||||
|
try_black_triangle_boxes_work
|
||||||
|
|
||||||
|
输入:全图 RGB + Stage1 的 ring_roi_xyxy。
|
||||||
|
在 Stage1 裁切图(与训练一致的 slab)上跑 黑三角 YOLO,得到若干个 子框(black_boxes_work,坐标在 裁切图/work 系)。
|
||||||
|
try_triangle_scoring 内
|
||||||
|
|
||||||
|
若 black_yolo_boxes_work 非空:
|
||||||
|
按配置在 Stage1 全分辨率灰度(或缩略灰度,视 det_scale / TRIANGLE_BLACK_YOLO_PATCH_GRAY_SOURCE)上,对每个子框裁 patch,跑 _extract_triangle_from_yolo_patch(子框内:Otsu → 失败再单次 Adaptive + 轮廓 + 形状/颜色)。
|
||||||
|
median_leg 过滤,再 四点分配 ID。
|
||||||
|
若 ≥3 个(通常 4 个)有效:认为 Stage2 成功,跳过 整幅 Stage1 上的 detect_triangle_markers。
|
||||||
|
若 不足 3 个 且未关 fallback:在 缩略后的整幅 work 灰度上再走 detect_triangle_markers(整图 Otsu + 整图 Adaptive×block_sizes + 各类 fallback),与「不用黑三角模型时的传统主路径」同类。
|
||||||
|
后续
|
||||||
|
|
||||||
|
角点从 det 坐标 ×inv_scale 回到 work,再 +roi 原点 回到全图;单应性、补第 4 点、PnP 等与另一条路相同。
|
||||||
|
耗时上多出来的部分:黑三角 YOLO 推理 + 每个子框一遍传统小流水线(成功时通常 不再付整图 detect_triangle_markers)。
|
||||||
|
|
||||||
|
流程 B:不用黑色三角形模型(纯传统定位三角)
|
||||||
|
典型配置(任一即可达到「不用黑三角模型」的效果):
|
||||||
|
|
||||||
|
TRIANGLE_BLACK_YOLO_ENABLE=False,或
|
||||||
|
TRIANGLE_BLACK_TRIANGLE_LOCATE_MODE="traditional"(即使模型开关开着也不跑黑三角 YOLO),或
|
||||||
|
没有 Stage1 ROI(roi_xyxy is None)时,当前逻辑下 也不会跑 Stage2 黑三角 YOLO。
|
||||||
|
此时 black_yolo_boxes_work=None(或不等价于「有子框」)。
|
||||||
|
|
||||||
|
步骤概要:
|
||||||
|
|
||||||
|
try_triangle_scoring 内
|
||||||
|
不跑 子框 _extract_triangle_from_yolo_patch。
|
||||||
|
直接在 img_det(缩略后的 work) 上调用 detect_triangle_markers:
|
||||||
|
全局 Otsu(若 TRIANGLE_SKIP_GLOBAL_OTSU_EXTRACT_ON_YOLO_ROI 在有 ROI 时可能 不算 Otsu 轮廓,但仍会生成 Otsu 图供后续用);
|
||||||
|
可选 象限 ROI(TRIANGLE_ROI_ENABLED);
|
||||||
|
整图 Adaptive(TRIANGLE_ADAPTIVE_BLOCK_SIZES,例如 (11,));
|
||||||
|
不足再走 放宽 approxPolyDP、BlackHat 等。
|
||||||
|
后面同样是过滤、四点组合/象限分配、单应性、PnP 等。
|
||||||
|
特点:没有黑三角 NPU 时间,也 没有「按框重复 4 次子框传统」;但要在 一整张(缩略)ROI 图 上跑一套更重的 整图 pipeline。
|
||||||
|
|
||||||
|
对照一句话
|
||||||
|
用黑三角 YOLO(流程 A) 不用黑三角 YOLO(流程 B)
|
||||||
|
Stage2
|
||||||
|
黑三角模型给子框 → 子框内 Otsu + 至多一次 Adaptive
|
||||||
|
无 Stage2 模型
|
||||||
|
三角角点从哪来
|
||||||
|
优先 子框传统;不够再 整图 detect_triangle_markers
|
||||||
|
只有 整图 detect_triangle_markers
|
||||||
|
和「全图是否只做 Adaptive」
|
||||||
|
子框 不是只做 Adaptive;整图回退时也与全图路径一致(先 Otsu 等)
|
||||||
|
整图路径 也不是只做 Adaptive
|
||||||
|
靶环 YOLO(Stage1 裁切)在 A/B 里都可以开或关,与「黑三角模型」是独立开关。
|
||||||
|
|
||||||
|
|
||||||
21
main.py
21
main.py
@@ -30,6 +30,7 @@ from ota_manager import ota_manager
|
|||||||
from hardware import hardware_manager
|
from hardware import hardware_manager
|
||||||
from camera_manager import camera_manager
|
from camera_manager import camera_manager
|
||||||
from shoot_manager import process_shot, preload_triangle_calib
|
from shoot_manager import process_shot, preload_triangle_calib
|
||||||
|
from target_roi_yolo import preload_yolo_detector
|
||||||
|
|
||||||
|
|
||||||
def laser_calibration_worker():
|
def laser_calibration_worker():
|
||||||
@@ -148,6 +149,26 @@ def cmd_str():
|
|||||||
except Exception:
|
except Exception:
|
||||||
pass
|
pass
|
||||||
|
|
||||||
|
# 2.7 预加载 YOLO(靶环 ROI + 黑三角);dual_buff=False 时无需 warmup 消除一帧延迟
|
||||||
|
try:
|
||||||
|
_preload_yolo = bool(getattr(config, "TRIANGLE_YOLO_PRELOAD_ON_BOOT", True))
|
||||||
|
_loc_black = str(
|
||||||
|
getattr(config, "TRIANGLE_BLACK_TRIANGLE_LOCATE_MODE", "yolo")
|
||||||
|
).lower().strip()
|
||||||
|
if _loc_black not in ("yolo", "traditional"):
|
||||||
|
_loc_black = "yolo"
|
||||||
|
_need_black_preload = (
|
||||||
|
bool(getattr(config, "TRIANGLE_BLACK_YOLO_ENABLE", False))
|
||||||
|
and _loc_black == "yolo"
|
||||||
|
and bool(getattr(config, "TRIANGLE_BLACK_YOLO_PRELOAD_ON_BOOT", True))
|
||||||
|
)
|
||||||
|
_preload_yolo = _preload_yolo or _need_black_preload
|
||||||
|
if _preload_yolo:
|
||||||
|
preload_yolo_detector(logger)
|
||||||
|
except Exception as e:
|
||||||
|
if logger:
|
||||||
|
logger.warning(f"[YOLO-ROI] 启动预加载异常(不影响后续射箭): {e}")
|
||||||
|
|
||||||
# 3. 启动时检查:是否需要恢复备份
|
# 3. 启动时检查:是否需要恢复备份
|
||||||
pending_path = f"{config.APP_DIR}/ota_pending.json"
|
pending_path = f"{config.APP_DIR}/ota_pending.json"
|
||||||
if os.path.exists(pending_path):
|
if os.path.exists(pending_path):
|
||||||
|
|||||||
BIN
model_270139.cvimodel
Normal file
BIN
model_270139.cvimodel
Normal file
Binary file not shown.
13
model_270139.mud
Normal file
13
model_270139.mud
Normal file
@@ -0,0 +1,13 @@
|
|||||||
|
|
||||||
|
[basic]
|
||||||
|
type = cvimodel
|
||||||
|
model = model_270139.cvimodel
|
||||||
|
|
||||||
|
[extra]
|
||||||
|
model_type = yolov5
|
||||||
|
input_type = rgb
|
||||||
|
mean = 0, 0, 0
|
||||||
|
scale = 0.00392156862745098, 0.00392156862745098, 0.00392156862745098
|
||||||
|
anchors = 10, 13, 16, 30, 33, 23, 30, 61, 62, 45, 59, 119, 116, 90, 156, 198, 373, 326
|
||||||
|
labels = 黑三角和圆环
|
||||||
|
|
||||||
BIN
model_270820.cvimodel
Normal file
BIN
model_270820.cvimodel
Normal file
Binary file not shown.
13
model_270820.mud
Normal file
13
model_270820.mud
Normal file
@@ -0,0 +1,13 @@
|
|||||||
|
|
||||||
|
[basic]
|
||||||
|
type = cvimodel
|
||||||
|
model = model_270820.cvimodel
|
||||||
|
|
||||||
|
[extra]
|
||||||
|
model_type = yolov5
|
||||||
|
input_type = rgb
|
||||||
|
mean = 0, 0, 0
|
||||||
|
scale = 0.00392156862745098, 0.00392156862745098, 0.00392156862745098
|
||||||
|
anchors = 10, 13, 16, 30, 33, 23, 30, 61, 62, 45, 59, 119, 116, 90, 156, 198, 373, 326
|
||||||
|
labels = triangle
|
||||||
|
|
||||||
124
power.py
124
power.py
@@ -141,24 +141,114 @@ def is_charging(threshold_ma=10.0):
|
|||||||
|
|
||||||
|
|
||||||
def voltage_to_percent(voltage):
|
def voltage_to_percent(voltage):
|
||||||
"""根据电压估算电池百分比(查表插值)"""
|
"""
|
||||||
|
根据电压估算电池百分比(高密度查表插值 + 滤波)。
|
||||||
|
|
||||||
|
- 电压先做 5 点移动平均(抑制瞬时抖动)
|
||||||
|
- SOC 再做一阶低通(抑制“跳电量”)
|
||||||
|
|
||||||
|
注意:
|
||||||
|
- 该方法仍是“开路电压→SOC”的近似;负载较大/瞬时大电流时电压会下沉,SOC 会偏低。
|
||||||
|
- 滤波会带来滞后:电量变化会更平滑,但更新更慢。
|
||||||
|
"""
|
||||||
if voltage is None:
|
if voltage is None:
|
||||||
return 0
|
return 0
|
||||||
points = [
|
try:
|
||||||
(4.20, 100), (4.10, 95), (4.05, 85), (4.00, 75), (3.95, 65),
|
v = float(voltage)
|
||||||
(3.90, 55), (3.85, 45), (3.80, 35), (3.75, 25), (3.70, 15),
|
except Exception:
|
||||||
(3.65, 5), (3.60, 0)
|
|
||||||
]
|
|
||||||
if voltage >= points[0][0]:
|
|
||||||
return 100
|
|
||||||
if voltage <= points[-1][0]:
|
|
||||||
return 0
|
return 0
|
||||||
for i in range(len(points) - 1):
|
if v <= 0:
|
||||||
v1, p1 = points[i]
|
return 0
|
||||||
v2, p2 = points[i + 1]
|
return int(round(_BATTERY_MONITOR.get_soc(v)))
|
||||||
if voltage >= v2:
|
|
||||||
ratio = (voltage - v1) / (v2 - v1)
|
|
||||||
percent = p1 + (p2 - p1) * ratio
|
class BatteryMonitor:
|
||||||
return max(0, min(100, int(round(percent))))
|
"""
|
||||||
return 0
|
电压→SOC 估算器(查表 + 线性插值 + 双重滤波)。
|
||||||
|
|
||||||
|
说明:
|
||||||
|
- 表为单节锂电“静态电压”近似曲线;不同电池/温度/老化会有偏差。
|
||||||
|
- 这里不区分充电/放电曲线(滞后),主要用于“显示电量/粗略判断”。
|
||||||
|
"""
|
||||||
|
|
||||||
|
def __init__(self, avg_window: int = 5, alpha: float = 0.2):
|
||||||
|
# 电压-SOC对照表(电压从高到低)
|
||||||
|
self.voltages = [
|
||||||
|
4.20, 4.15, 4.10, 4.05, 4.00,
|
||||||
|
3.95, 3.90, 3.88, 3.85, 3.82,
|
||||||
|
3.80, 3.78, 3.75, 3.72, 3.70,
|
||||||
|
3.65, 3.60, 3.55, 3.50, 3.45,
|
||||||
|
3.40, 3.35, 3.30, 3.20, 2.50,
|
||||||
|
]
|
||||||
|
self.socs = [
|
||||||
|
100, 98, 95, 90, 85,
|
||||||
|
80, 75, 72, 68, 64,
|
||||||
|
60, 56, 52, 48, 44,
|
||||||
|
38, 32, 26, 20, 14,
|
||||||
|
10, 6, 3, 1, 0,
|
||||||
|
]
|
||||||
|
|
||||||
|
self.avg_window = max(1, int(avg_window))
|
||||||
|
self.alpha = float(alpha) if alpha is not None else 0.2
|
||||||
|
if not (0.0 < self.alpha <= 1.0):
|
||||||
|
self.alpha = 0.2
|
||||||
|
|
||||||
|
self.voltage_history = []
|
||||||
|
self.last_soc = 50.0
|
||||||
|
|
||||||
|
def _voltage_to_soc_raw(self, voltage: float) -> float:
|
||||||
|
# 越界
|
||||||
|
if voltage >= self.voltages[0]:
|
||||||
|
return 100.0
|
||||||
|
if voltage <= self.voltages[-1]:
|
||||||
|
return 0.0
|
||||||
|
|
||||||
|
# 表是降序,二分查找
|
||||||
|
left, right = 0, len(self.voltages) - 1
|
||||||
|
while left <= right:
|
||||||
|
mid = (left + right) // 2
|
||||||
|
vm = self.voltages[mid]
|
||||||
|
if vm == voltage:
|
||||||
|
return float(self.socs[mid])
|
||||||
|
elif vm < voltage:
|
||||||
|
right = mid - 1
|
||||||
|
else:
|
||||||
|
left = mid + 1
|
||||||
|
|
||||||
|
# 线性插值:right 在高电压侧,left 在低电压侧(降序表)
|
||||||
|
# 例:voltages = [4.2,4.15,...],则 v_high=voltages[right] >= voltage >= voltages[left]=v_low
|
||||||
|
v_high, v_low = float(self.voltages[right]), float(self.voltages[left])
|
||||||
|
soc_high, soc_low = float(self.socs[right]), float(self.socs[left])
|
||||||
|
if abs(v_high - v_low) < 1e-9:
|
||||||
|
return soc_low
|
||||||
|
soc = soc_low + (voltage - v_low) * (soc_high - soc_low) / (v_high - v_low)
|
||||||
|
return soc
|
||||||
|
|
||||||
|
def get_soc(self, raw_voltage: float) -> float:
|
||||||
|
# 1) 电压滤波(移动平均)
|
||||||
|
self.voltage_history.append(float(raw_voltage))
|
||||||
|
if len(self.voltage_history) > self.avg_window:
|
||||||
|
self.voltage_history.pop(0)
|
||||||
|
voltage = sum(self.voltage_history) / float(len(self.voltage_history))
|
||||||
|
|
||||||
|
# 2) 查表插值
|
||||||
|
raw_soc = self._voltage_to_soc_raw(voltage)
|
||||||
|
|
||||||
|
# 3) SOC 低通滤波
|
||||||
|
a = self.alpha
|
||||||
|
self.last_soc = a * raw_soc + (1.0 - a) * float(self.last_soc)
|
||||||
|
|
||||||
|
# clip
|
||||||
|
if self.last_soc < 0.0:
|
||||||
|
self.last_soc = 0.0
|
||||||
|
if self.last_soc > 100.0:
|
||||||
|
self.last_soc = 100.0
|
||||||
|
return float(self.last_soc)
|
||||||
|
|
||||||
|
|
||||||
|
# 模块级单例:保留历史,实现平滑(进程重启会重置)
|
||||||
|
_BATTERY_MONITOR = BatteryMonitor(
|
||||||
|
avg_window=int(getattr(config, "BATTERY_SOC_AVG_WINDOW", 5)),
|
||||||
|
alpha=float(getattr(config, "BATTERY_SOC_LPF_ALPHA", 0.2)),
|
||||||
|
)
|
||||||
|
|
||||||
|
|||||||
225
shoot_manager.py
225
shoot_manager.py
@@ -1,5 +1,6 @@
|
|||||||
import os
|
import os
|
||||||
import threading
|
import threading
|
||||||
|
import time as time_std
|
||||||
|
|
||||||
import config
|
import config
|
||||||
from camera_manager import camera_manager
|
from camera_manager import camera_manager
|
||||||
@@ -96,7 +97,7 @@ def analyze_shot(frame, laser_point=None):
|
|||||||
K, dist_coef, pos = _get_triangle_calib()
|
K, dist_coef, pos = _get_triangle_calib()
|
||||||
use_tri = K is not None and dist_coef is not None and pos
|
use_tri = K is not None and dist_coef is not None and pos
|
||||||
|
|
||||||
def _build_circle_result(cdata):
|
def _build_circle_result(cdata, yolo_roi_xyxy=None):
|
||||||
"""从圆形检测结果构建 analyze_shot 返回值。"""
|
"""从圆形检测结果构建 analyze_shot 返回值。"""
|
||||||
r_img, center, radius, method, best_radius1, ellipse_params = cdata
|
r_img, center, radius, method, best_radius1, ellipse_params = cdata
|
||||||
dx, dy = None, None
|
dx, dy = None, None
|
||||||
@@ -104,7 +105,7 @@ def analyze_shot(frame, laser_point=None):
|
|||||||
if center and radius:
|
if center and radius:
|
||||||
dx, dy = laser_manager.compute_laser_position(center, (x, y), radius, method)
|
dx, dy = laser_manager.compute_laser_position(center, (x, y), radius, method)
|
||||||
d_m = estimate_distance(best_radius1) if best_radius1 else distance_m_first
|
d_m = estimate_distance(best_radius1) if best_radius1 else distance_m_first
|
||||||
return {
|
out = {
|
||||||
"success": True,
|
"success": True,
|
||||||
"result_img": r_img,
|
"result_img": r_img,
|
||||||
"center": center, "radius": radius, "method": method,
|
"center": center, "radius": radius, "method": method,
|
||||||
@@ -114,6 +115,9 @@ def analyze_shot(frame, laser_point=None):
|
|||||||
"offset_method": "yellow_ellipse" if ellipse_params else "yellow_circle",
|
"offset_method": "yellow_ellipse" if ellipse_params else "yellow_circle",
|
||||||
"distance_method": "yellow_radius",
|
"distance_method": "yellow_radius",
|
||||||
}
|
}
|
||||||
|
if yolo_roi_xyxy is not None:
|
||||||
|
out["yolo_roi_xyxy"] = yolo_roi_xyxy
|
||||||
|
return out
|
||||||
|
|
||||||
if not use_tri:
|
if not use_tri:
|
||||||
# 三角形未配置,直接跑圆形检测
|
# 三角形未配置,直接跑圆形检测
|
||||||
@@ -121,68 +125,147 @@ def analyze_shot(frame, laser_point=None):
|
|||||||
detect_circle_v3(frame, laser_point, img_cv=img_cv)
|
detect_circle_v3(frame, laser_point, img_cv=img_cv)
|
||||||
)
|
)
|
||||||
|
|
||||||
# ── Step 4: 三角形 + 圆形并行检测 ─────────────────────────────────────────────
|
# ── Step 4: 先独占跑三角形,超时或失败后再跑圆形(不与圆心并行,避免抢 CPU)──
|
||||||
# 两个线程共享只读的 img_cv,互不干扰
|
roi_xyxy = None
|
||||||
|
yolo_ring_ms = 0.0
|
||||||
|
yolo_black_ms = 0.0
|
||||||
|
if getattr(config, "TRIANGLE_YOLO_ROI_ENABLE", False):
|
||||||
|
_t_yolo_ring = time_std.perf_counter()
|
||||||
|
try:
|
||||||
|
from target_roi_yolo import try_get_triangle_roi_from_yolo
|
||||||
|
roi_xyxy = try_get_triangle_roi_from_yolo(
|
||||||
|
frame, img_cv.shape[1], img_cv.shape[0], logger
|
||||||
|
)
|
||||||
|
except Exception as e:
|
||||||
|
if logger:
|
||||||
|
logger.warning(f"[YOLO-ROI] {e}")
|
||||||
|
finally:
|
||||||
|
yolo_ring_ms = (time_std.perf_counter() - _t_yolo_ring) * 1000.0
|
||||||
|
|
||||||
|
_loc_mode = str(
|
||||||
|
getattr(config, "TRIANGLE_BLACK_TRIANGLE_LOCATE_MODE", "yolo")
|
||||||
|
).lower().strip()
|
||||||
|
if _loc_mode not in ("yolo", "traditional"):
|
||||||
|
_loc_mode = "yolo"
|
||||||
|
|
||||||
|
black_boxes_work = None
|
||||||
|
_run_stage2_black_yolo = (
|
||||||
|
_loc_mode == "yolo"
|
||||||
|
and getattr(config, "TRIANGLE_BLACK_YOLO_ENABLE", False)
|
||||||
|
and roi_xyxy is not None
|
||||||
|
)
|
||||||
|
if _run_stage2_black_yolo:
|
||||||
|
_t_yolo_black = time_std.perf_counter()
|
||||||
|
try:
|
||||||
|
from target_roi_yolo import try_black_triangle_boxes_work
|
||||||
|
|
||||||
|
black_boxes_work = try_black_triangle_boxes_work(
|
||||||
|
img_cv, roi_xyxy, logger
|
||||||
|
)
|
||||||
|
except Exception as e:
|
||||||
|
if logger:
|
||||||
|
logger.warning(f"[YOLO-BLACK] {e}")
|
||||||
|
finally:
|
||||||
|
yolo_black_ms = (time_std.perf_counter() - _t_yolo_black) * 1000.0
|
||||||
|
elif (
|
||||||
|
logger
|
||||||
|
and _loc_mode == "traditional"
|
||||||
|
and roi_xyxy is not None
|
||||||
|
and getattr(config, "TRIANGLE_BLACK_YOLO_ENABLE", False)
|
||||||
|
):
|
||||||
|
logger.info(
|
||||||
|
"[TRI] TRIANGLE_BLACK_TRIANGLE_LOCATE_MODE=traditional:跳过 Stage2 黑三角 YOLO,"
|
||||||
|
"仅在 Stage1 裁切内跑整幅传统三角检测"
|
||||||
|
)
|
||||||
|
|
||||||
tri_result = {}
|
tri_result = {}
|
||||||
circle_result = {}
|
|
||||||
|
|
||||||
def _run_triangle():
|
def _run_triangle():
|
||||||
try:
|
try:
|
||||||
logger.info(f"[TRI] begin {datetime.now()}")
|
logger.info(f"[TRI] begin {datetime.now()}")
|
||||||
logger.info(f"[TRI] K: {K}, dist: {dist_coef}, pos: {pos}, {datetime.now()}")
|
logger.info(f"[TRI] K: {K}, dist: {dist_coef}, pos: {pos}, {datetime.now()}")
|
||||||
|
_t_wall_try = time_std.perf_counter()
|
||||||
tri = try_triangle_scoring(
|
tri = try_triangle_scoring(
|
||||||
img_cv, (x, y), pos, K, dist_coef,
|
img_cv, (x, y), pos, K, dist_coef,
|
||||||
size_range=getattr(config, "TRIANGLE_SIZE_RANGE", (8, 500)),
|
size_range=getattr(config, "TRIANGLE_SIZE_RANGE", (8, 500)),
|
||||||
|
roi_xyxy=roi_xyxy,
|
||||||
|
black_yolo_boxes_work=black_boxes_work,
|
||||||
|
yolo_ring_ms=yolo_ring_ms,
|
||||||
|
yolo_black_ms=yolo_black_ms,
|
||||||
)
|
)
|
||||||
|
_wall_try_ms = (time_std.perf_counter() - _t_wall_try) * 1000.0
|
||||||
|
if logger and bool(getattr(config, "TRIANGLE_LOG_E2E_TIMING", True)):
|
||||||
|
_e2e = float(yolo_ring_ms) + float(yolo_black_ms) + float(_wall_try_ms)
|
||||||
|
logger.info(
|
||||||
|
f"[TRI] timing_e2e_triangle_ms={_e2e:.1f} "
|
||||||
|
f"(yolo_ring={float(yolo_ring_ms):.1f} yolo_black={float(yolo_black_ms):.1f} "
|
||||||
|
f"try_triangle_wall={_wall_try_ms:.1f} locate_mode={_loc_mode})"
|
||||||
|
)
|
||||||
logger.info(f"[TRI] tri: {tri}, {datetime.now()}")
|
logger.info(f"[TRI] tri: {tri}, {datetime.now()}")
|
||||||
tri_result['data'] = tri
|
tri_result['data'] = tri
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
logger.error(f"[TRI] 三角形路径异常: {e}")
|
logger.error(f"[TRI] 三角形路径异常: {e}")
|
||||||
tri_result['data'] = {'ok': False}
|
tri_result['data'] = {'ok': False}
|
||||||
|
|
||||||
def _run_circle():
|
|
||||||
try:
|
|
||||||
circle_result['data'] = detect_circle_v3(frame, laser_point, img_cv=img_cv)
|
|
||||||
except Exception as e:
|
|
||||||
logger.error(f"[CIRCLE] 圆形检测异常: {e}")
|
|
||||||
circle_result['data'] = (frame, None, None, None, None, None)
|
|
||||||
|
|
||||||
t_tri = threading.Thread(target=_run_triangle, daemon=True)
|
t_tri = threading.Thread(target=_run_triangle, daemon=True)
|
||||||
t_cir = threading.Thread(target=_run_circle, daemon=True)
|
|
||||||
t_tri.start()
|
t_tri.start()
|
||||||
t_cir.start()
|
|
||||||
|
|
||||||
# 最多等待三角形 TRIANGLE_TIMEOUT_MS(默认 1000ms)
|
tri_timeout_s = float(getattr(config, "TRIANGLE_TIMEOUT_MS", 2000)) / 1000.0
|
||||||
tri_timeout_s = float(getattr(config, "TRIANGLE_TIMEOUT_MS", 1000)) / 1000.0
|
|
||||||
t_tri.join(timeout=tri_timeout_s)
|
t_tri.join(timeout=tri_timeout_s)
|
||||||
if t_tri.is_alive():
|
|
||||||
# 超时:直接放弃三角形结果,回退圆心(圆心线程通常已跑完)
|
|
||||||
logger.warning(f"[TRI] timeout>{tri_timeout_s:.2f}s,回退圆心算法")
|
|
||||||
t_cir.join()
|
|
||||||
return _build_circle_result(
|
|
||||||
circle_result.get('data') or (frame, None, None, None, None, None)
|
|
||||||
)
|
|
||||||
|
|
||||||
tri = tri_result.get('data', {})
|
def _tri_ok_validated(tri):
|
||||||
|
try:
|
||||||
|
import numpy as _np
|
||||||
|
ok = bool(tri.get('ok'))
|
||||||
|
if not ok:
|
||||||
|
return False
|
||||||
|
|
||||||
# 保险校验:避免三角形返回 nan/inf 或退化点仍被上报
|
|
||||||
try:
|
|
||||||
import numpy as _np
|
|
||||||
tri_ok = bool(tri.get('ok'))
|
|
||||||
if tri_ok:
|
|
||||||
dxv = tri.get("dx_cm")
|
dxv = tri.get("dx_cm")
|
||||||
dyv = tri.get("dy_cm")
|
dyv = tri.get("dy_cm")
|
||||||
H = tri.get("homography")
|
H = tri.get("homography")
|
||||||
if not _np.isfinite(dxv) or not _np.isfinite(dyv):
|
if not _np.isfinite(dxv) or not _np.isfinite(dyv):
|
||||||
tri_ok = False
|
logger.warning("[TRI] dx/dy 非有限值,判定为误检")
|
||||||
elif H is not None and not _np.all(_np.isfinite(H)):
|
return False
|
||||||
tri_ok = False
|
if H is not None and not _np.all(_np.isfinite(H)):
|
||||||
except Exception:
|
logger.warning("[TRI] 单应矩阵含非有限值,判定为误检")
|
||||||
tri_ok = bool(tri.get('ok'))
|
return False
|
||||||
|
|
||||||
if tri_ok:
|
# ── 检查1:单应矩阵 x/y 缩放比(靶标是正方形,H[0,0]≈H[1,1])──
|
||||||
logger.info(f"[TRI] end {datetime.now()} — 使用三角形结果(dx={tri['dx_cm']:.2f},dy={tri['dy_cm']:.2f}cm)")
|
if H is not None:
|
||||||
return {
|
sx = abs(float(H[0, 0]))
|
||||||
|
sy = abs(float(H[1, 1]))
|
||||||
|
if sy > 1e-6:
|
||||||
|
hxy_ratio = sx / sy
|
||||||
|
# 正常拍摄比值在 0.6~1.7 之间;超出则四点严重变形,说明有误检
|
||||||
|
if not (0.6 <= hxy_ratio <= 1.7):
|
||||||
|
logger.warning(
|
||||||
|
f"[TRI] 单应矩阵 sx/sy={hxy_ratio:.2f} 偏差过大,判定为误检,回退圆心"
|
||||||
|
)
|
||||||
|
return False
|
||||||
|
|
||||||
|
# ── 检查2:可选配置距离上下限(写 0 表示不启用)──────────────────
|
||||||
|
dist_m = tri.get("distance_m")
|
||||||
|
if dist_m is not None:
|
||||||
|
try:
|
||||||
|
import config as _vc
|
||||||
|
d_min = float(getattr(_vc, "TRIANGLE_DISTANCE_MIN_M", 0.0))
|
||||||
|
d_max = float(getattr(_vc, "TRIANGLE_DISTANCE_MAX_M", 0.0))
|
||||||
|
except Exception:
|
||||||
|
d_min, d_max = 0.0, 0.0
|
||||||
|
if d_min > 0 and d_max > d_min:
|
||||||
|
if not (d_min <= dist_m <= d_max):
|
||||||
|
logger.warning(
|
||||||
|
f"[TRI] 距离 {dist_m:.2f}m 超出配置范围 [{d_min},{d_max}],判定为误检,回退圆心"
|
||||||
|
)
|
||||||
|
return False
|
||||||
|
|
||||||
|
return True
|
||||||
|
except Exception:
|
||||||
|
return bool(tri.get('ok'))
|
||||||
|
|
||||||
|
def _build_tri_result(tri, yolo_roi_xyxy=None):
|
||||||
|
out = {
|
||||||
"success": True,
|
"success": True,
|
||||||
"result_img": frame,
|
"result_img": frame,
|
||||||
"center": None, "radius": None,
|
"center": None, "radius": None,
|
||||||
@@ -194,15 +277,38 @@ def analyze_shot(frame, laser_point=None):
|
|||||||
"offset_method": tri.get("offset_method") or "triangle_homography",
|
"offset_method": tri.get("offset_method") or "triangle_homography",
|
||||||
"distance_method": tri.get("distance_method") or "pnp_triangle",
|
"distance_method": tri.get("distance_method") or "pnp_triangle",
|
||||||
"tri_markers": tri.get("markers", []),
|
"tri_markers": tri.get("markers", []),
|
||||||
|
"tri_markers_completed": tri.get("markers_completed", []),
|
||||||
"tri_homography": tri.get("homography"),
|
"tri_homography": tri.get("homography"),
|
||||||
}
|
}
|
||||||
|
if yolo_roi_xyxy is not None:
|
||||||
|
out["yolo_roi_xyxy"] = yolo_roi_xyxy
|
||||||
|
return out
|
||||||
|
|
||||||
# 三角形失败,等圆形结果(已并行跑完,几乎无额外等待)
|
# 三角形在超时内完成
|
||||||
t_cir.join()
|
if not t_tri.is_alive():
|
||||||
logger.info(f"[TRI] end(fallback) {datetime.now()}")
|
tri = tri_result.get('data', {})
|
||||||
return _build_circle_result(
|
if _tri_ok_validated(tri):
|
||||||
circle_result.get('data') or (frame, None, None, None, None, None)
|
logger.info(f"[TRI] end {datetime.now()} — 使用三角形结果(dx={tri['dx_cm']:.2f},dy={tri['dy_cm']:.2f}cm)")
|
||||||
)
|
return _build_tri_result(tri, roi_xyxy)
|
||||||
|
logger.info(f"[TRI] end(tri_failed, fallback circle) {datetime.now()}")
|
||||||
|
else:
|
||||||
|
logger.warning(f"[TRI] 超时 {tri_timeout_s:.2f}s 仍未结束,启动圆心算法(三角形仍在后台)")
|
||||||
|
|
||||||
|
# 三角形超时或失败 → 跑圆心;圆心跑完后再检查三角形是否已结束
|
||||||
|
try:
|
||||||
|
cdata = detect_circle_v3(frame, laser_point, img_cv=img_cv)
|
||||||
|
except Exception as e:
|
||||||
|
logger.error(f"[CIRCLE] 圆形检测异常: {e}")
|
||||||
|
cdata = (frame, None, None, None, None, None)
|
||||||
|
|
||||||
|
# 圆心跑完后,若三角形恰好已经结束且结果有效,优先用三角形
|
||||||
|
if not t_tri.is_alive():
|
||||||
|
tri = tri_result.get('data', {})
|
||||||
|
if _tri_ok_validated(tri):
|
||||||
|
logger.info(f"[TRI] 圆心跑完后三角形已就绪 — 优先使用三角形结果(dx={tri['dx_cm']:.2f},dy={tri['dy_cm']:.2f}cm)")
|
||||||
|
return _build_tri_result(tri, roi_xyxy)
|
||||||
|
|
||||||
|
return _build_circle_result(cdata, roi_xyxy)
|
||||||
|
|
||||||
|
|
||||||
def process_shot(adc_val):
|
def process_shot(adc_val):
|
||||||
@@ -241,7 +347,13 @@ def process_shot(adc_val):
|
|||||||
offset_method = analysis_result.get("offset_method", "yellow_circle")
|
offset_method = analysis_result.get("offset_method", "yellow_circle")
|
||||||
distance_method = analysis_result.get("distance_method", "yellow_radius")
|
distance_method = analysis_result.get("distance_method", "yellow_radius")
|
||||||
tri_markers = analysis_result.get("tri_markers", [])
|
tri_markers = analysis_result.get("tri_markers", [])
|
||||||
|
tri_markers_completed = analysis_result.get("tri_markers_completed", [])
|
||||||
tri_homography = analysis_result.get("tri_homography")
|
tri_homography = analysis_result.get("tri_homography")
|
||||||
|
yolo_roi_xyxy = analysis_result.get("yolo_roi_xyxy")
|
||||||
|
draw_yolo_roi = (
|
||||||
|
yolo_roi_xyxy is not None
|
||||||
|
and getattr(config, "TRIANGLE_YOLO_DRAW_ROI_ON_SHOT", True)
|
||||||
|
)
|
||||||
x, y = laser_point
|
x, y = laser_point
|
||||||
|
|
||||||
# 三角形路径成功时 center/radius 为空是正常的;此时用 triangle 方法名用于保存文件名与上报字段 m
|
# 三角形路径成功时 center/radius 为空是正常的;此时用 triangle 方法名用于保存文件名与上报字段 m
|
||||||
@@ -312,6 +424,8 @@ def process_shot(adc_val):
|
|||||||
import numpy as _np
|
import numpy as _np
|
||||||
_img_cv = image.image2cv(result_img, False, False)
|
_img_cv = image.image2cv(result_img, False, False)
|
||||||
|
|
||||||
|
# YOLO 靶环框在 vision.enqueue_save_shot 的 worker 里绘制,避免阻塞主流程
|
||||||
|
|
||||||
# 三角形轮廓 + 直角顶点 + ID
|
# 三角形轮廓 + 直角顶点 + ID
|
||||||
for _m in tri_markers:
|
for _m in tri_markers:
|
||||||
_corners = _np.array(_m["corners"], dtype=_np.int32)
|
_corners = _np.array(_m["corners"], dtype=_np.int32)
|
||||||
@@ -322,6 +436,26 @@ def process_shot(adc_val):
|
|||||||
(_cx - 18, _cy - 12),
|
(_cx - 18, _cy - 12),
|
||||||
_cv2.FONT_HERSHEY_SIMPLEX, 0.55, (0, 255, 0), 1)
|
_cv2.FONT_HERSHEY_SIMPLEX, 0.55, (0, 255, 0), 1)
|
||||||
|
|
||||||
|
# 3点补全的虚拟角点:只画中心点 + 文本,避免误认为真实检测到的三角形
|
||||||
|
try:
|
||||||
|
if tri_markers_completed:
|
||||||
|
for _m in tri_markers_completed:
|
||||||
|
if not _m.get("is_virtual"):
|
||||||
|
continue
|
||||||
|
_cx, _cy = int(_m["center"][0]), int(_m["center"][1])
|
||||||
|
_cv2.circle(_img_cv, (_cx, _cy), 6, (255, 0, 255), 2) # 紫色空心圈
|
||||||
|
_cv2.putText(
|
||||||
|
_img_cv,
|
||||||
|
f"VT{_m['id']}",
|
||||||
|
(_cx - 22, _cy - 12),
|
||||||
|
_cv2.FONT_HERSHEY_SIMPLEX,
|
||||||
|
0.55,
|
||||||
|
(255, 0, 255),
|
||||||
|
1,
|
||||||
|
)
|
||||||
|
except Exception:
|
||||||
|
pass
|
||||||
|
|
||||||
# 靶心(H_inv @ [0,0]):小红圆
|
# 靶心(H_inv @ [0,0]):小红圆
|
||||||
_center_px = None
|
_center_px = None
|
||||||
if tri_homography is not None:
|
if tri_homography is not None:
|
||||||
@@ -365,6 +499,10 @@ def process_shot(adc_val):
|
|||||||
|
|
||||||
result_img = image.cv2image(_img_cv, False, False)
|
result_img = image.cv2image(_img_cv, False, False)
|
||||||
|
|
||||||
|
elif draw_yolo_roi:
|
||||||
|
# 仅 YOLO 标注时也不在主线程画框,交给存图 worker
|
||||||
|
pass
|
||||||
|
|
||||||
# 2. 激光十字线
|
# 2. 激光十字线
|
||||||
_lc = image.Color(config.LASER_COLOR[0], config.LASER_COLOR[1], config.LASER_COLOR[2])
|
_lc = image.Color(config.LASER_COLOR[0], config.LASER_COLOR[1], config.LASER_COLOR[2])
|
||||||
result_img.draw_line(int(x - config.LASER_LENGTH), int(y),
|
result_img.draw_line(int(x - config.LASER_LENGTH), int(y),
|
||||||
@@ -390,6 +528,7 @@ def process_shot(adc_val):
|
|||||||
distance_m,
|
distance_m,
|
||||||
shot_id=shot_id,
|
shot_id=shot_id,
|
||||||
photo_dir=config.PHOTO_DIR if config.SAVE_IMAGE_ENABLED else None,
|
photo_dir=config.PHOTO_DIR if config.SAVE_IMAGE_ENABLED else None,
|
||||||
|
yolo_roi_xyxy=yolo_roi_xyxy if draw_yolo_roi else None,
|
||||||
)
|
)
|
||||||
|
|
||||||
if logger:
|
if logger:
|
||||||
|
|||||||
1332
triangle_target.py
1332
triangle_target.py
File diff suppressed because it is too large
Load Diff
155
vision.py
155
vision.py
@@ -678,6 +678,91 @@ def estimate_distance(pixel_radius):
|
|||||||
return 0.0
|
return 0.0
|
||||||
return (config.REAL_RADIUS_CM * config.FOCAL_LENGTH_PIX) / pixel_radius / 100.0
|
return (config.REAL_RADIUS_CM * config.FOCAL_LENGTH_PIX) / pixel_radius / 100.0
|
||||||
|
|
||||||
|
def _draw_yolo_roi_on_rgb_numpy(img_cv, yolo_roi_xyxy):
|
||||||
|
"""
|
||||||
|
在 RGB numpy 图像上绘制靶环 YOLO ROI(与原先 shoot_manager 主线程绘制语义一致)。
|
||||||
|
供存图 worker 异步调用,不阻塞射箭主流程。
|
||||||
|
"""
|
||||||
|
if yolo_roi_xyxy is None:
|
||||||
|
return
|
||||||
|
if not getattr(config, "TRIANGLE_YOLO_DRAW_ROI_ON_SHOT", True):
|
||||||
|
return
|
||||||
|
try:
|
||||||
|
rx0, ry0, rx1, ry1 = (int(round(float(v))) for v in yolo_roi_xyxy)
|
||||||
|
ih, iw = img_cv.shape[:2]
|
||||||
|
rx0 = max(0, min(rx0, iw - 1))
|
||||||
|
ry0 = max(0, min(ry0, ih - 1))
|
||||||
|
rx1 = max(rx0 + 1, min(rx1, iw))
|
||||||
|
ry1 = max(ry0 + 1, min(ry1, ih))
|
||||||
|
cv2.rectangle(
|
||||||
|
img_cv,
|
||||||
|
(rx0, ry0),
|
||||||
|
(rx1 - 1, ry1 - 1),
|
||||||
|
(0, 255, 255),
|
||||||
|
2,
|
||||||
|
)
|
||||||
|
cv2.putText(
|
||||||
|
img_cv,
|
||||||
|
"YOLO ROI",
|
||||||
|
(max(0, rx0), max(16, ry0 - 4)),
|
||||||
|
cv2.FONT_HERSHEY_SIMPLEX,
|
||||||
|
0.55,
|
||||||
|
(0, 255, 255),
|
||||||
|
1,
|
||||||
|
)
|
||||||
|
except Exception:
|
||||||
|
pass
|
||||||
|
|
||||||
|
|
||||||
|
def prune_old_images_in_dir(photo_dir, max_images, logger=None, log_prefix="[VISION]"):
|
||||||
|
"""
|
||||||
|
若目录内 bmp/jpg/jpeg 超过 max_images,按 mtime 从最旧开始删,直到数量 ≤ max_images。
|
||||||
|
与射箭主图目录清理规则一致,供 PHOTO_DIR、stage2_roi 等共用。
|
||||||
|
"""
|
||||||
|
try:
|
||||||
|
max_images = int(max_images)
|
||||||
|
except (TypeError, ValueError):
|
||||||
|
return
|
||||||
|
if max_images <= 0 or not photo_dir:
|
||||||
|
return
|
||||||
|
if logger is None:
|
||||||
|
logger = logger_manager.logger
|
||||||
|
try:
|
||||||
|
if not os.path.isdir(photo_dir):
|
||||||
|
return
|
||||||
|
image_files = []
|
||||||
|
for f in os.listdir(photo_dir):
|
||||||
|
if f.endswith((".bmp", ".jpg", ".jpeg")):
|
||||||
|
filepath = os.path.join(photo_dir, f)
|
||||||
|
try:
|
||||||
|
mtime = os.path.getmtime(filepath)
|
||||||
|
image_files.append((mtime, filepath, f))
|
||||||
|
except Exception:
|
||||||
|
pass
|
||||||
|
if len(image_files) <= max_images:
|
||||||
|
return
|
||||||
|
image_files.sort(key=lambda x: x[0])
|
||||||
|
to_delete = len(image_files) - max_images
|
||||||
|
deleted_count = 0
|
||||||
|
for _, filepath, fname in image_files[:to_delete]:
|
||||||
|
try:
|
||||||
|
os.remove(filepath)
|
||||||
|
deleted_count += 1
|
||||||
|
if logger:
|
||||||
|
logger.debug(f"{log_prefix} 删除旧图片: {fname}")
|
||||||
|
except Exception as e:
|
||||||
|
if logger:
|
||||||
|
logger.warning(f"{log_prefix} 删除旧图片失败 {fname}: {e}")
|
||||||
|
if logger and deleted_count > 0:
|
||||||
|
logger.info(
|
||||||
|
f"{log_prefix} 已清理 {deleted_count} 张旧图,"
|
||||||
|
f"目录保留至多 {max_images} 张: {photo_dir}"
|
||||||
|
)
|
||||||
|
except Exception as e:
|
||||||
|
if logger:
|
||||||
|
logger.warning(f"{log_prefix} 清理旧图片时出错(可忽略): {e}")
|
||||||
|
|
||||||
|
|
||||||
def estimate_pixel(physical_distance_cm, target_distance_m):
|
def estimate_pixel(physical_distance_cm, target_distance_m):
|
||||||
"""
|
"""
|
||||||
根据物理距离和目标距离计算对应的像素偏移
|
根据物理距离和目标距离计算对应的像素偏移
|
||||||
@@ -696,7 +781,8 @@ def estimate_pixel(physical_distance_cm, target_distance_m):
|
|||||||
|
|
||||||
|
|
||||||
def _save_shot_image_impl(img_cv, center, radius, method, ellipse_params,
|
def _save_shot_image_impl(img_cv, center, radius, method, ellipse_params,
|
||||||
laser_point, distance_m, shot_id=None, photo_dir=None):
|
laser_point, distance_m, shot_id=None, photo_dir=None,
|
||||||
|
yolo_roi_xyxy=None):
|
||||||
"""
|
"""
|
||||||
内部实现:在 img_cv (numpy HWC RGB) 上绘制标注并保存。
|
内部实现:在 img_cv (numpy HWC RGB) 上绘制标注并保存。
|
||||||
由 save_shot_image(同步)和存图 worker(异步)调用。
|
由 save_shot_image(同步)和存图 worker(异步)调用。
|
||||||
@@ -735,6 +821,8 @@ def _save_shot_image_impl(img_cv, center, radius, method, ellipse_params,
|
|||||||
distance_str = str(round((distance_m or 0.0) * 100))
|
distance_str = str(round((distance_m or 0.0) * 100))
|
||||||
filename = f"{photo_dir}/{method_str}_{int(x)}_{int(y)}_{distance_str}_{img_count:04d}.jpg"
|
filename = f"{photo_dir}/{method_str}_{int(x)}_{int(y)}_{distance_str}_{img_count:04d}.jpg"
|
||||||
|
|
||||||
|
_draw_yolo_roi_on_rgb_numpy(img_cv, yolo_roi_xyxy)
|
||||||
|
|
||||||
logger = logger_manager.logger
|
logger = logger_manager.logger
|
||||||
if logger:
|
if logger:
|
||||||
if shot_id:
|
if shot_id:
|
||||||
@@ -786,37 +874,7 @@ def _save_shot_image_impl(img_cv, center, radius, method, ellipse_params,
|
|||||||
else:
|
else:
|
||||||
logger.debug(f"图像已保存(无靶心,含激光十字线): {filename}")
|
logger.debug(f"图像已保存(无靶心,含激光十字线): {filename}")
|
||||||
|
|
||||||
# 清理旧图片:如果目录下图片超过100张,删除最老的
|
prune_old_images_in_dir(photo_dir, config.MAX_IMAGES, logger, "[VISION]")
|
||||||
try:
|
|
||||||
image_files = []
|
|
||||||
for f in os.listdir(photo_dir):
|
|
||||||
if f.endswith(('.bmp', '.jpg', '.jpeg')):
|
|
||||||
filepath = os.path.join(photo_dir, f)
|
|
||||||
try:
|
|
||||||
mtime = os.path.getmtime(filepath)
|
|
||||||
image_files.append((mtime, filepath, f))
|
|
||||||
except Exception:
|
|
||||||
pass
|
|
||||||
|
|
||||||
from config import MAX_IMAGES
|
|
||||||
if len(image_files) > MAX_IMAGES:
|
|
||||||
image_files.sort(key=lambda x: x[0])
|
|
||||||
to_delete = len(image_files) - MAX_IMAGES
|
|
||||||
deleted_count = 0
|
|
||||||
for _, filepath, fname in image_files[:to_delete]:
|
|
||||||
try:
|
|
||||||
os.remove(filepath)
|
|
||||||
deleted_count += 1
|
|
||||||
if logger:
|
|
||||||
logger.debug(f"[VISION] 删除旧图片: {fname}")
|
|
||||||
except Exception as e:
|
|
||||||
if logger:
|
|
||||||
logger.warning(f"[VISION] 删除旧图片失败 {fname}: {e}")
|
|
||||||
if logger and deleted_count > 0:
|
|
||||||
logger.info(f"[VISION] 已清理 {deleted_count} 张旧图片,当前剩余 {MAX_IMAGES} 张")
|
|
||||||
except Exception as e:
|
|
||||||
if logger:
|
|
||||||
logger.warning(f"[VISION] 清理旧图片时出错(可忽略): {e}")
|
|
||||||
|
|
||||||
return filename
|
return filename
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
@@ -864,7 +922,8 @@ def start_save_shot_worker():
|
|||||||
|
|
||||||
|
|
||||||
def enqueue_save_shot(result_img, center, radius, method, ellipse_params,
|
def enqueue_save_shot(result_img, center, radius, method, ellipse_params,
|
||||||
laser_point, distance_m, shot_id=None, photo_dir=None):
|
laser_point, distance_m, shot_id=None, photo_dir=None,
|
||||||
|
yolo_roi_xyxy=None):
|
||||||
"""
|
"""
|
||||||
将存图任务放入队列,由 worker 异步保存。主线程传入 result_img 的复制,不阻塞。
|
将存图任务放入队列,由 worker 异步保存。主线程传入 result_img 的复制,不阻塞。
|
||||||
"""
|
"""
|
||||||
@@ -880,7 +939,18 @@ def enqueue_save_shot(result_img, center, radius, method, ellipse_params,
|
|||||||
if logger:
|
if logger:
|
||||||
logger.error(f"[VISION] enqueue_save_shot 复制图像失败: {e}")
|
logger.error(f"[VISION] enqueue_save_shot 复制图像失败: {e}")
|
||||||
return
|
return
|
||||||
task = (img_copy, center, radius, method, ellipse_params, laser_point, distance_m, shot_id, photo_dir)
|
task = (
|
||||||
|
img_copy,
|
||||||
|
center,
|
||||||
|
radius,
|
||||||
|
method,
|
||||||
|
ellipse_params,
|
||||||
|
laser_point,
|
||||||
|
distance_m,
|
||||||
|
shot_id,
|
||||||
|
photo_dir,
|
||||||
|
yolo_roi_xyxy,
|
||||||
|
)
|
||||||
try:
|
try:
|
||||||
_save_queue.put_nowait(task)
|
_save_queue.put_nowait(task)
|
||||||
except queue.Full:
|
except queue.Full:
|
||||||
@@ -890,7 +960,8 @@ def enqueue_save_shot(result_img, center, radius, method, ellipse_params,
|
|||||||
|
|
||||||
|
|
||||||
def save_shot_image(result_img, center, radius, method, ellipse_params,
|
def save_shot_image(result_img, center, radius, method, ellipse_params,
|
||||||
laser_point, distance_m, shot_id=None, photo_dir=None):
|
laser_point, distance_m, shot_id=None, photo_dir=None,
|
||||||
|
yolo_roi_xyxy=None):
|
||||||
"""
|
"""
|
||||||
保存射击图像(带标注)。同步调用,会阻塞。
|
保存射击图像(带标注)。同步调用,会阻塞。
|
||||||
主流程建议使用 enqueue_save_shot;此处保留供校准、测试等场景使用。
|
主流程建议使用 enqueue_save_shot;此处保留供校准、测试等场景使用。
|
||||||
@@ -901,8 +972,18 @@ def save_shot_image(result_img, center, radius, method, ellipse_params,
|
|||||||
photo_dir = config.PHOTO_DIR
|
photo_dir = config.PHOTO_DIR
|
||||||
try:
|
try:
|
||||||
img_cv = image.image2cv(result_img, False, False)
|
img_cv = image.image2cv(result_img, False, False)
|
||||||
return _save_shot_image_impl(img_cv, center, radius, method, ellipse_params,
|
return _save_shot_image_impl(
|
||||||
laser_point, distance_m, shot_id, photo_dir)
|
img_cv,
|
||||||
|
center,
|
||||||
|
radius,
|
||||||
|
method,
|
||||||
|
ellipse_params,
|
||||||
|
laser_point,
|
||||||
|
distance_m,
|
||||||
|
shot_id,
|
||||||
|
photo_dir,
|
||||||
|
yolo_roi_xyxy,
|
||||||
|
)
|
||||||
except Exception as e:
|
except Exception as e:
|
||||||
logger = logger_manager.logger
|
logger = logger_manager.logger
|
||||||
if logger:
|
if logger:
|
||||||
|
|||||||
Reference in New Issue
Block a user