From 2acf920a8718306224322a190e53e3fefbd9fda1 Mon Sep 17 00:00:00 2001
From: CHAMPION923 <1056156912@qq.com>
Date: Fri, 30 May 2025 16:30:37 +0800
Subject: [PATCH] =?UTF-8?q?TractorVision=E5=88=9D=E6=9C=9F=E7=A7=BB?=
=?UTF-8?q?=E6=A4=8D?=
MIME-Version: 1.0
Content-Type: text/plain; charset=UTF-8
Content-Transfer-Encoding: 8bit
---
.idea/.gitignore | 8 +
.idea/hirres_tractor_vision.iml | 12 +
.../inspectionProfiles/profiles_settings.xml | 6 +
.idea/misc.xml | 7 +
.idea/modules.xml | 8 +
config/2d_camera.json | 12 +
config/2d_camera.json.bak | 12 +
config/camera_sn.json | 11 +
config/camera_sn.json.bak | 28 +
debug/__init__.py | 0
lib/__init__.py | 0
lib/alg/__init__.py | 0
lib/alg/distance_respect_tof.py | 55 +
lib/alg/image_processing_3d.py | 183 ++
lib/alg/line_detection.py | 115 +
lib/alg/predict_yolo8_template.py | 84 +
lib/alg/track_detection.py | 173 ++
lib/camera/ArenaCamera.py | 294 ++
lib/camera/MindVisionCamera.py | 153 ++
lib/camera/__init__.py | 0
lib/camera/mvsdk.py | 2394 +++++++++++++++++
lib/cfg/__init__.py | 0
lib/cfg/cfg.py | 42 +
lib/gui/__init__.py | 0
lib/io/__init__.py | 0
lib/io/process2d.py | 30 +
lib/io/process3d.py | 26 +
lib/mod/__init__.py | 0
lib/presenter/__init__.py | 0
lib/presenter/presenter.py | 211 ++
lib/tcp/__init__.py | 0
lib/tcp/tcp_server.py | 26 +
main.py | 5 +
pyrightconfig.json | 3 +
requirements.txt | Bin 0 -> 130 bytes
run.sh | 0
36 files changed, 3898 insertions(+)
create mode 100644 .idea/.gitignore
create mode 100644 .idea/hirres_tractor_vision.iml
create mode 100644 .idea/inspectionProfiles/profiles_settings.xml
create mode 100644 .idea/misc.xml
create mode 100644 .idea/modules.xml
create mode 100644 config/2d_camera.json
create mode 100644 config/2d_camera.json.bak
create mode 100644 config/camera_sn.json
create mode 100644 config/camera_sn.json.bak
create mode 100644 debug/__init__.py
create mode 100644 lib/__init__.py
create mode 100644 lib/alg/__init__.py
create mode 100644 lib/alg/distance_respect_tof.py
create mode 100644 lib/alg/image_processing_3d.py
create mode 100644 lib/alg/line_detection.py
create mode 100644 lib/alg/predict_yolo8_template.py
create mode 100644 lib/alg/track_detection.py
create mode 100644 lib/camera/ArenaCamera.py
create mode 100644 lib/camera/MindVisionCamera.py
create mode 100644 lib/camera/__init__.py
create mode 100644 lib/camera/mvsdk.py
create mode 100644 lib/cfg/__init__.py
create mode 100644 lib/cfg/cfg.py
create mode 100644 lib/gui/__init__.py
create mode 100644 lib/io/__init__.py
create mode 100644 lib/io/process2d.py
create mode 100644 lib/io/process3d.py
create mode 100644 lib/mod/__init__.py
create mode 100644 lib/presenter/__init__.py
create mode 100644 lib/presenter/presenter.py
create mode 100644 lib/tcp/__init__.py
create mode 100644 lib/tcp/tcp_server.py
create mode 100644 main.py
create mode 100644 pyrightconfig.json
create mode 100644 requirements.txt
create mode 100755 run.sh
diff --git a/.idea/.gitignore b/.idea/.gitignore
new file mode 100644
index 0000000..35410ca
--- /dev/null
+++ b/.idea/.gitignore
@@ -0,0 +1,8 @@
+# 默认忽略的文件
+/shelf/
+/workspace.xml
+# 基于编辑器的 HTTP 客户端请求
+/httpRequests/
+# Datasource local storage ignored files
+/dataSources/
+/dataSources.local.xml
diff --git a/.idea/hirres_tractor_vision.iml b/.idea/hirres_tractor_vision.iml
new file mode 100644
index 0000000..fa7a615
--- /dev/null
+++ b/.idea/hirres_tractor_vision.iml
@@ -0,0 +1,12 @@
+
+
+
+
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/.idea/inspectionProfiles/profiles_settings.xml b/.idea/inspectionProfiles/profiles_settings.xml
new file mode 100644
index 0000000..105ce2d
--- /dev/null
+++ b/.idea/inspectionProfiles/profiles_settings.xml
@@ -0,0 +1,6 @@
+
+
+
+
+
+
\ No newline at end of file
diff --git a/.idea/misc.xml b/.idea/misc.xml
new file mode 100644
index 0000000..9de2865
--- /dev/null
+++ b/.idea/misc.xml
@@ -0,0 +1,7 @@
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/.idea/modules.xml b/.idea/modules.xml
new file mode 100644
index 0000000..2db8935
--- /dev/null
+++ b/.idea/modules.xml
@@ -0,0 +1,8 @@
+
+
+
+
+
+
+
+
\ No newline at end of file
diff --git a/config/2d_camera.json b/config/2d_camera.json
new file mode 100644
index 0000000..91a5255
--- /dev/null
+++ b/config/2d_camera.json
@@ -0,0 +1,12 @@
+{
+ "camera": [
+ {
+ "sn":"054042423001",
+ "title":"前2D"
+ },
+ {
+ "sn":"054042423002",
+ "title":"后2D"
+ }
+ ]
+}
diff --git a/config/2d_camera.json.bak b/config/2d_camera.json.bak
new file mode 100644
index 0000000..91a5255
--- /dev/null
+++ b/config/2d_camera.json.bak
@@ -0,0 +1,12 @@
+{
+ "camera": [
+ {
+ "sn":"054042423001",
+ "title":"前2D"
+ },
+ {
+ "sn":"054042423002",
+ "title":"后2D"
+ }
+ ]
+}
diff --git a/config/camera_sn.json b/config/camera_sn.json
new file mode 100644
index 0000000..69ac4c3
--- /dev/null
+++ b/config/camera_sn.json
@@ -0,0 +1,11 @@
+{
+ "camera": [
+ {"sn": "234000035", "title": "前左避障"},
+ {"sn": "233801341", "title": "前右避障"},
+ {"sn": "233800055", "title": "后左避障"},
+ {"sn": "233800056", "title": "后右避障"},
+ {"sn": "233900305", "title": "前右上轨"},
+ {"sn": "233900303", "title": "后左上轨"}
+ ]
+ }
+
\ No newline at end of file
diff --git a/config/camera_sn.json.bak b/config/camera_sn.json.bak
new file mode 100644
index 0000000..74a5a6f
--- /dev/null
+++ b/config/camera_sn.json.bak
@@ -0,0 +1,28 @@
+{
+ "camera": [
+ {
+ "sn":"234000035",
+ "title":"前左避障"
+ },
+ {
+ "sn":"233801341",
+ "title":"前右避障"
+ },
+ {
+ "sn":"233900305",
+ "title":"前右上轨"
+ },
+ {
+ "sn":"233800055",
+ "title":"后左避障"
+ },
+ {
+ "sn":"233800056",
+ "title":"后右避障"
+ },
+ {
+ "sn":"233900303",
+ "title":"后左上轨"
+ }
+ ]
+}
diff --git a/debug/__init__.py b/debug/__init__.py
new file mode 100644
index 0000000..e69de29
diff --git a/lib/__init__.py b/lib/__init__.py
new file mode 100644
index 0000000..e69de29
diff --git a/lib/alg/__init__.py b/lib/alg/__init__.py
new file mode 100644
index 0000000..e69de29
diff --git a/lib/alg/distance_respect_tof.py b/lib/alg/distance_respect_tof.py
new file mode 100644
index 0000000..f09b805
--- /dev/null
+++ b/lib/alg/distance_respect_tof.py
@@ -0,0 +1,55 @@
+# distance_detector.py
+import numpy as np
+
+# 每个相机SN对应的ROI配置(中心坐标和基准尺寸)
+# 画框测距
+ROI_SETTINGS = {
+ '233800055': {'center': (220, 340), 'base_size': (200, 200)},
+ '234000035': {'center': (220, 340), 'base_size': (200, 200)},
+ # 可根据需要添加更多相机
+}
+# 默认基准深度(毫米)
+DEFAULT_BASE_DEPTH_MM = 2000
+
+class DistanceDetector:
+ """
+ 基于 TOF 深度图的动态 ROI 距离检测器,ROI 参数内置到算法中。
+
+ 算法流程:
+ 1. 使用相机 SN 对应的预设 ROI 中心和大小。
+ 2. 在像素中心读取深度值 d。
+ 3. 根据基准深度与当前深度的比例动态计算 ROI 大小。
+ 4. 在 ROI 内提取非零深度值并计算平均值作为目标距离(毫米)。
+ """
+ def __init__(self, sn, base_depth_mm=DEFAULT_BASE_DEPTH_MM):
+ if sn not in ROI_SETTINGS:
+ raise ValueError(f"No ROI settings for camera SN: {sn}")
+ cfg = ROI_SETTINGS[sn]
+ self.cx, self.cy = cfg['center']
+ self.base_w, self.base_h = cfg['base_size']
+ self.base_depth = base_depth_mm
+
+ def _compute_dynamic_roi(self, depth_image):
+ h, w = depth_image.shape
+ d = float(depth_image[int(self.cy), int(self.cx)])
+ if d <= 0:
+ return None
+ scale = self.base_depth / d
+ rw = int(self.base_w * scale)
+ rh = int(self.base_h * scale)
+ x1 = max(0, int(self.cx - rw // 2))
+ y1 = max(0, int(self.cy - rh // 2))
+ x2 = min(w, x1 + rw)
+ y2 = min(h, y1 + rh)
+ return x1, y1, x2, y2
+
+ def compute_distance(self, depth_image):
+ coords = self._compute_dynamic_roi(depth_image)
+ if coords is None:
+ return None
+ x1, y1, x2, y2 = coords
+ roi = depth_image[y1:y2, x1:x2]
+ valid = roi[roi > 0]
+ if valid.size == 0:
+ return None
+ return float(np.mean(valid))
diff --git a/lib/alg/image_processing_3d.py b/lib/alg/image_processing_3d.py
new file mode 100644
index 0000000..e4d25c1
--- /dev/null
+++ b/lib/alg/image_processing_3d.py
@@ -0,0 +1,183 @@
+import os
+import cv2
+import numpy as np
+import ctypes
+import math
+import open3d as o3d
+import time
+
+
+# +++++++++++++++++++++++++++++++++++++++++++++++++++++保存深度图像函数+++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+def save_depth_image(image_data, width, height, sn, queue,image_count):
+ # 将图像数据转换为OpenCV格式
+ depth_image_array = ctypes.cast(image_data, ctypes.POINTER(ctypes.c_uint16 * (width.value * height.value))).contents
+ depth_image_np = np.array(depth_image_array).reshape(height.value, width.value)
+ # 对每个像素点的深度数据乘以 0.25
+ # 使用OpenCV保存图像
+ image_name = f"{image_count}DepthImage_{sn}.png"
+ # output_directory = "OutputDirectory/Linux/x64Release/Images"
+ output_directory = "src/Python/src/ToolsFuncsDemo/ImagesTest/Trac_up_down02"
+
+ os.makedirs(output_directory, exist_ok=True)
+ output_path = os.path.join(output_directory, image_name)
+ cv2.imwrite(output_path, depth_image_np)
+ print(f"Depth image saved as {output_path} for camera {sn}")
+ queue.put(f"Depth image saved as {output_path} for camera {sn}")
+ return f"Depth image saved as {output_path} for camera {sn}"
+#+++++++++++++++++++++++++++++++++++++++++++++++++++++++障碍物检测++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+ #+++++++++++++++++++++++++++++++++++++++++++用统计滤波去除孤立点++++++++++++++++++++++++++++++++++++++
+# def statistical_outlier_removal(point_cloud,nb_neighbors, std_ratio):
+# """
+# 使用统计滤波去除孤立点
+# :param point_cloud: Open3D点云对象
+# :param nb_neighbors: 每个点考虑的邻域点数
+# :param std_ratio: 标准差倍数,用于判断是否为离群点
+# :return: 去除孤立点后的点云对象
+# """
+
+
+# # # 执行统计滤波
+# cl, ind = point_cloud.remove_radius_outlier(20,10)
+
+# # # 选择过滤后的点云
+# point_cloud_filtered = point_cloud.select_by_index(ind)
+# return point_cloud_filtered
+
+
+def statistical_outlier_removal(point_cloud, nb_neighbors=20, std_ratio=2.0):
+ cl, ind = point_cloud.remove_statistical_outlier(nb_neighbors=nb_neighbors, std_ratio=std_ratio)
+ return cl
+
+
+ #+++++++++++++++++++++++++++++++++++++++++++ 深度图-》点云++++++++++++++++++++++++++++++++++++++
+
+
+def depth_to_point_cloud(depth_image_data,x_image_np,y_image_np,width, height, min_depth, max_depth):
+ """
+ 将深度图像转换为点云,使用像素坐标作为x和y,并筛选出有效范围内的点
+ :param depth_image_data: 深度图像数据 (二维数组,每个元素表示深度值,单位为毫米)
+ :param width: 图像宽度 (整数)
+ :param height: 图像高度 (整数)
+ :param min_depth: 最小有效深度 (毫米),默认为500毫米 (0.5米)
+ :param max_depth: 最大有效深度 (毫米),默认为6000毫米 (6米)
+ :return: Open3D点云对象
+ """
+
+ # 确保宽度和高度是整数
+ if not isinstance(width, int) or not isinstance(height, int):
+ raise ValueError("Width and height must be integers")
+
+ # 创建点云对象
+ point_cloud = o3d.geometry.PointCloud()
+
+ # 创建点云数据
+ points = []
+ colors = []
+
+ # 确保深度图像数据是 NumPy 数组
+ depth_image_data = np.array(depth_image_data)
+ x_image_data = np.array(x_image_np)
+ y_image_data = np.array(y_image_np)
+
+
+ # 相机中心位置
+ center_x = width / 2
+ center_y = height / 2
+
+ for v in range(height):
+ for u in range(width):
+ # 获取深度值
+ z = depth_image_data[v, u]
+ # 检查深度值是否在有效范围内
+ if z < min_depth or z > max_depth:
+ continue
+
+ # 计算像素大小(毫米/像素)
+ pixel_size_x_mm = 2 * z * np.tan(np.radians(69 / 2)) / width
+ pixel_size_y_mm = 2 * z * np.tan(np.radians(51 / 2)) / height
+
+ # 计算以相机中心为原点的坐标,并调整坐标系
+ x = (u - center_x) # X 轴相对于相机中心
+ y = (center_y - v) # 相机的y+朝下
+
+ x_mm = x * pixel_size_x_mm
+ y_mm = y * pixel_size_y_mm
+
+ points.append([x_mm, y_mm, z])
+ colors.append([1.0, 0.0, 0.0]) # 设置颜色为红色
+
+ # 将点云数据转换为NumPy数组
+ points = np.array(points)
+ colors = np.array(colors)
+
+ # 设置点云的点和颜色
+ point_cloud.points = o3d.utility.Vector3dVector(points)
+ point_cloud.colors = o3d.utility.Vector3dVector(colors)
+
+ # # 可视化点云
+ # o3d.visualization.draw_geometries([point_cloud])
+ # 去除噪声(孤立点),根据现场情况再调整
+ start_time = time.perf_counter() # 记录开始时间
+ point_cloud = statistical_outlier_removal(point_cloud, 20, 1.0)
+ end_time = time.perf_counter() # 记录结束时间
+ runtime = end_time - start_time # 计算运行时间
+ # print(f"statistical_outlier_removal函数运行时间:{runtime:.6f} 秒")
+
+ return point_cloud
+
+#+++++++++++++++++++++++++++++++++++++++++++ 绘制立体矩形框并检测障碍物++++++++++++++++++++++++++++++++++++++
+
+def detect_obstacles_in_box(point_cloud, min_bound, max_bound, width, height, save_name="detected_obstacle.ply", visualize=False):
+ # 1. 滤波
+ filtered_point_cloud = statistical_outlier_removal(point_cloud, 20, 1.0)
+
+ # 2. 创建 AABB 框
+ box = o3d.geometry.AxisAlignedBoundingBox(min_bound=min_bound, max_bound=max_bound)
+ box.color = (0.0, 1.0, 0.0) # ✅ 绿色边框
+
+ # 3. 提取框内点
+ indices = box.get_point_indices_within_bounding_box(filtered_point_cloud.points)
+ if len(indices) == 0:
+ # print("未检测到任何点在框内")
+ return None, filtered_point_cloud
+
+ points = np.asarray(filtered_point_cloud.points)
+ colors = np.asarray(filtered_point_cloud.colors)
+
+ if len(colors) == 0:
+ colors = np.ones((len(points), 3)) # 白色
+ filtered_point_cloud.colors = o3d.utility.Vector3dVector(colors)
+ colors = np.asarray(filtered_point_cloud.colors)
+
+ # 框内红色,框外绿色
+ colors[indices] = [1.0, 0.0, 0.0]
+ mask = np.ones(len(points), dtype=bool)
+ mask[indices] = False
+ colors[mask] = [0.0, 1.0, 0.0]
+
+ # 最近点 → 黑色
+ reference_point = np.array([0.0, 0.0, 0.0])
+ obstacle_points = points[indices]
+ distances = np.linalg.norm(obstacle_points - reference_point, axis=1)
+ closest_index = np.argmin(distances)
+ closest_point = obstacle_points[closest_index]
+ min_distance = distances[closest_index]
+ global_closest_index = indices[closest_index]
+ colors[global_closest_index] = [0.0, 0.0, 0.0]
+
+ # 更新颜色
+ filtered_point_cloud.colors = o3d.utility.Vector3dVector(colors)
+
+ # ✅ 可视化
+ if visualize:
+ o3d.visualization.draw_geometries([filtered_point_cloud, box])
+
+
+
+ # TODO: 返回一个像素点和距离
+ return {
+ 'position': closest_point.tolist(),
+ 'distance': float(min_distance)
+ }, filtered_point_cloud
+
+
diff --git a/lib/alg/line_detection.py b/lib/alg/line_detection.py
new file mode 100644
index 0000000..cd5bcd5
--- /dev/null
+++ b/lib/alg/line_detection.py
@@ -0,0 +1,115 @@
+import cv2
+import numpy as np
+
+def detect_lines_in_depth_image(depth_image, roi,min_depth):
+ """
+ Detect lines in a depth image within a specified Region of Interest (ROI).
+
+ :param depth_image: The depth image in grayscale16 format.
+ :param roi: The Region of Interest (ROI) to limit the detection region within the depth image.
+ :return: The detected lines with coordinates relative to the original depth image.
+ """
+ lines_list = []
+ # Convert the depth image to a format suitable for line detection using OpenCV
+ # Scale the depth image from uint16 to uint8
+ # Extract the ROI from the depth image
+ x, y, w, h = roi
+ roi_image = depth_image[y:y+h, x:x+w]
+
+ min_dist = np.min(roi_image)
+ max_dist = np.max(roi_image)
+
+ print(f"ROI shape:{roi_image.shape}")
+ print(f"ROI深度范围:{min_dist} - {max_dist}")
+ # norm_img = cv2.normalize(roi_image, None, 0,255, cv2.NORM_MINMAX, cv2.CV_8U)
+
+ min_dist = min_depth
+ # max_dist = 1800
+ norm_img = (roi_image-min_dist)/(max_dist-min_dist)
+ norm_img = norm_img * 255
+ norm_img = np.clip(norm_img,0,255)
+ norm_img = norm_img.astype(np.uint8)
+
+# cv2.imwrite('dbg_norm.png',norm_img)
+
+
+ edges = cv2.Canny(norm_img,15,30,apertureSize=3)
+# cv2.imwrite('dbg_edges.png',edges)
+
+ # Use OpenCV's line detection algorithm (e.g., HoughLines or HoughLinesP) to detect lines within the specified ROI
+ lines = cv2.HoughLinesP(edges, 1, np.pi/180, 20, minLineLength=10, maxLineGap=100)
+
+ norm_depth_img = cv2.normalize(depth_image, None, 0,255, cv2.NORM_MINMAX, cv2.CV_8U)
+ colored_img = cv2.cvtColor(norm_depth_img,cv2.COLOR_GRAY2BGR)
+ # Adjust the line coordinates to be relative to the original depth image
+ if lines is not None:
+ for points in lines:
+ # Extracted points nested in the list
+ x1,y1,x2,y2=points[0]
+ x1=x1+x
+ y1=y1+y
+ x2=x2+x
+ y2=y2+y
+ # Draw the lines joing the points
+ # On the original image
+ cv2.line(colored_img,(x1,y1),(x2,y2),(0,255,0),2)
+ # Maintain a simples lookup list for points
+ lines_list.append([(x1,y1),(x2,y2)])
+
+ # Save the result image
+ # cv2.imwrite('dbg_detectedLines.png',colored_img)
+ # Return the detected lines with adjusted coordinates
+ return lines_list
+
+def calculate_line_angle(line):
+ """
+ 计算线条与水平线(x轴)之间的角度。
+
+ :param line: 线条的两个端点坐标,格式为 [(x1, y1), (x2, y2)]
+ :return: 线条与水平线之间的角度(以度为单位,范围为0-180度)
+ """
+ # 提取两个点的坐标
+ (x1, y1), (x2, y2) = line
+
+ # 计算斜率,处理垂直线的情况
+ if x2 - x1 == 0:
+ return 90.0 # 垂直线
+
+ # 计算斜率
+ slope = (y2 - y1) / (x2 - x1)
+
+ # 计算角度(弧度)并转换为度
+ angle = np.arctan(slope) * 180 / np.pi
+
+ # 确保角度为正(0-180度范围内)
+ if angle < 0:
+ angle += 180
+ #转换成与相机中线之间的角度
+
+ return angle
+
+
+
+
+def calculate_distance_point_to_line(point, line):
+ """
+ 计算一个点到一条线的距离。
+
+ :param point: 点的坐标,格式为 (x, y)
+ :param line: 线的两个端点坐标,格式为 [(x1, y1), (x2, y2)]
+ :return: 点到线的距离
+ """
+ (x0, y0) = point
+ (x1, y1), (x2, y2) = line
+ numerator = abs((y2 - y1) * x0 - (x2 - x1) * y0 + x2 * y1 - y2 * x1)
+ denominator = np.sqrt((y2 - y1) ** 2 + (x2 - x1) ** 2)
+ return (numerator / denominator)*2.5+5
+
+if __name__ == '__main__':
+ img = cv2.imread('dbg_233900303_z.png',cv2.IMREAD_UNCHANGED)
+ line_list = detect_lines_in_depth_image(img,(320,240,640,480),1100)
+ print(line_list)
+ for line in line_list:
+ angle = calculate_line_angle(line)
+ dist = calculate_distance_point_to_line((320,240),line)
+ print(f'angle={angle} dist={dist}')
diff --git a/lib/alg/predict_yolo8_template.py b/lib/alg/predict_yolo8_template.py
new file mode 100644
index 0000000..751e747
--- /dev/null
+++ b/lib/alg/predict_yolo8_template.py
@@ -0,0 +1,84 @@
+import cv2
+from ultralytics import YOLO
+
+# YOLOv8Detector类:用于加载YOLO模型,进行目标检测并在图像上绘制信息
+class YOLOv8Detector:
+ def __init__(self):
+ """
+ 初始化YOLOv8检测器
+ :param classes: 自定义类别名称列表(暂未使用)
+ """
+ self.model = YOLO(r"model/yolov8n.pt") # 使用YOLOv8官方预训练模型
+ # self.model = YOLO(r"model/best.pt") # 使用自训练模型
+
+ self.class_names = self.model.names # 获取类别名称
+ self._frame_counter = 0 # 帧计数器(用于调试打印)
+
+ # +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+ # 执行YOLO目标检测,并在图像中绘制检测框、中心坐标和尺寸信息(不再过滤类别)
+ # +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
+ def detect_and_draw(self, image):
+ height, width = image.shape[:2]
+
+ # 使用YOLO模型进行检测
+ results = self.model(image, imgsz=640)
+ frame_id = self._frame_counter
+ self._frame_counter += 1
+
+ result_info = [] # 存储每个目标的检测信息
+ # print(f"\n[FRAME {frame_id}] Detection Result:")
+
+ for result in results:
+ boxes = result.boxes
+
+ # 遍历所有检测框(不再按类别筛选)
+ for i in range(len(boxes)):
+ cls_id = int(boxes.cls[i].item()) # 类别索引
+ cls_name = self.class_names[cls_id] if cls_id < len(self.class_names) else f"class_{cls_id}"
+ score = float(boxes.conf[i].item()) # 置信度
+
+ # (1)boxes.xyxy[i]提取第i个种类边界框坐标[x1, y1, x2, y2];(2)tolist()实现将PyTorch 的张量(Tensor)[x1, y1, x2, y2]转换为 普通的 Python 列表;(3)使用 map() 函数将列表中的 浮点数坐标转换为整数坐标,因为像素坐标用于图像绘制时必须是整数。
+ x1_box, y1_box, x2_box, y2_box = map(int, boxes.xyxy[i].tolist())
+
+ # 计算中心点与宽高
+ x_center = (x1_box + x2_box) / 2
+ y_center = (y1_box + y2_box) / 2
+ bbox_width = x2_box - x1_box
+ bbox_height = y2_box - y1_box
+
+ # 打印调试信息
+ # print(f"[{cls_name}] Score: {score:.2f}")
+ # print(f" Center: ({x_center:.1f}, {y_center:.1f})")
+ # print(f" BBox: Width={bbox_width}px, Height={bbox_height}px")
+ # print(f" 左上角坐标: ({x1_box}px, {y1_box}px)")
+
+ # 绘制检测框(绿色),参数2表示线宽
+ cv2.rectangle(image, (x1_box, y1_box), (x2_box, y2_box), (0, 255, 0), 2)
+
+ # 绘制框右上角顶部标签(类别名+得分)
+ label = f"{cls_name} {score:.2f}"
+ cv2.putText(image, label, (x2_box, y1_box - 60),
+ cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 255, 0), 3)
+ # 绘制框右上角顶部标签(类别名+得分)
+ cv2.putText(image, f"L-corner-coor:{x1_box, y1_box}", (x1_box, y1_box - 20),
+ cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 255, 0), 3)
+
+ # 在框底部左下角显示中心坐标和尺寸信息
+ cv2.putText(image, f"Center: ({x_center:.1f}, {y_center:.1f})",
+ (x1_box, y2_box + 70),
+ cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 255, 255), 3)
+ cv2.putText(image, f"Width: {bbox_width}px, Height: {bbox_height}px",
+ (x1_box, y2_box + 150),
+ cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 255, 255), 3)
+
+ # 保存检测信息字典."L-corner-coor":(x1_box, y1_box)左上角坐标点
+ result_dict = {
+ "class": cls_name,
+ "score": score,
+ "center": (x_center, y_center),
+ "bbox": (bbox_width, bbox_height),
+ "L-corner-coor":(x1_box, y1_box)
+ }
+ result_info.append(result_dict)
+
+ return image, result_info
diff --git a/lib/alg/track_detection.py b/lib/alg/track_detection.py
new file mode 100644
index 0000000..15c408b
--- /dev/null
+++ b/lib/alg/track_detection.py
@@ -0,0 +1,173 @@
+# 文件: tractor_vision/alg/track_detection.py
+import cv2
+import numpy as np
+import math
+from collections import deque
+
+# ——— 相机标定参数 ———
+FX = 474.0 # X轴焦距
+FY = 505.0 # Y轴焦距
+CX = 320.0 # CX 中心x轴中标
+CY = 240.0 # CY 中心y轴座标
+CAMERA_TILT_DEG = 10.0 # 向下为正
+
+# ——— ROI & 阈值 ———
+ROI = (190, 40, 250, 420)
+MIN_DEPTH = 1100
+ANGLE_TOL_DEG = 45
+
+
+def preprocess_depth(depth, blur_ksize=5, kernel_size=7):
+ """
+ - 中值滤波消噪
+ - 形态学闭运算填补空洞
+ """
+ d = cv2.medianBlur(depth, blur_ksize)
+ kernel = np.ones((kernel_size, kernel_size), np.uint8)
+ closed = cv2.morphologyEx(d, cv2.MORPH_CLOSE, kernel)
+ d[d == 0] = closed[d == 0]
+ return d
+
+
+def offset_after_rotation(line):
+ (x1, y1), (x2, y2) = line
+ phi = math.degrees(math.atan2(y2 - y1, x2 - x1))
+ rot = math.radians(90.0 - phi)
+ mx, my = (x1 + x2) / 2, (y1 + y2) / 2
+ dx, dy = mx - CX, my - CY
+ x_rot = dx * math.cos(rot) - dy * math.sin(rot)
+ return -x_rot, (int(mx), int(my))
+
+
+def compute_metrics(depth):
+ # NOTE: 先强行对数据进行转换,保持数据为uint16的副本
+ depth_mm = (
+ depth.copy().astype(np.uint16) if depth.dtype != np.uint16 else depth.copy()
+ )
+ # NOTE: 中值滤波消噪
+ den = preprocess_depth(depth_mm)
+ # NOTE: 裁剪出感兴趣的ROI区域进行分析
+ x, y, w, h = ROI
+ crop = den[y : y + h, x : x + w]
+ if not (crop >= MIN_DEPTH).any():
+ return None, None, None, None, depth_mm, ROI, None
+
+ # NOTE: 将深度裁剪区域 crop 归一化到0~255区间,并转换为 uint8 类型,方便后续边缘检测。
+ # 归一化是为了适配 OpenCV 的边缘检测算法对8位图像的需求。
+ norm = cv2.normalize(crop, None, 0, 255, cv2.NORM_MINMAX).astype("uint8")
+ # NOTE: 对归一化后的图像执行 Canny 边缘检测,提取边缘轮廓。
+ # 50和150是边缘检测的低高阈值。
+ edges = cv2.Canny(norm, 50, 150)
+ lines = cv2.HoughLinesP(edges, 1, np.pi / 180, 30, minLineLength=50, maxLineGap=10)
+ # NOTE: 如果没检测边缘直线,则返回空
+ if lines is None:
+ return None, None, None, None, depth_mm, ROI, None
+ # NOTE: 将摄像机俯仰角(单位度)转为弧度,后续角度计算时用。
+ tilt = math.radians(CAMERA_TILT_DEG)
+ # NOTE:初始化空列表,存放符合角度条件的候选轨道线。
+ cands = []
+ # NOTE: 遍历霍夫检测到的所有直线,每条线由两个端点坐标 (x1_, y1_) 和 (x2_, y2_) 表示。
+ for x1_, y1_, x2_, y2_ in lines.reshape(-1, 4):
+ # NOTE:将裁剪区域的坐标偏移加回,转换为深度图整体坐标系的位置。
+ # 因为霍夫检测是在裁剪区域内,需补偿ROI偏移。
+ p1 = (x1_ + x, y1_ + y)
+ p2 = (x2_ + x, y2_ + y)
+ # NOTE: 计算线段水平和垂直方向的向量分量
+ dx, dy = p2[0] - p1[0], p2[1] - p1[1]
+ # NOTE: 计算线段与垂直方向的角度(弧度)
+ raw = -math.atan2(dx, -dy)
+ # NOTE: 考虑摄像头俯仰角 tilt,修正线段的角度。把线段角度投影到水平面,得到真实的轨道角度。
+ grd = math.asin(math.sin(raw) * math.cos(tilt))
+ # NOTE: 角度转换成度数,并取绝对值。
+ ang = abs(math.degrees(grd))
+ # NOTE: 如果角度小于预设阈值 ANGLE_TOL_DEG(即近似垂直轨道的线),认为是候选轨道线,添加到列表。
+ if ang <= ANGLE_TOL_DEG:
+ cands.append({"line": (p1, p2), "mid_x": (p1[0] + p2[0]) / 2})
+ # NOTE: 如果没找到符合角度的候选线,返回 None。
+ if not cands:
+ return None, None, None, None, depth_mm, ROI, None
+ # NOTE: 选择最左边的轨道线作为“最佳”轨道线,依据中点横坐标最小。
+ best = min(cands, key=lambda c: c["mid_x"])
+ # NOTE: 拆包出最佳轨道线的两个端点坐标。
+ line = best["line"]
+ (x1, y1), (x2, y2) = line
+
+ # 交点
+ dxl, dyl = x2 - x1, y2 - y1
+ # NOTE: 计算轨道线与摄像头中心线(垂直线 x=CX)交点坐标。
+ # 如果轨道线不是垂直的,则通过线性插值求出交点 y 坐标。
+ # 如果轨道线垂直(dxl=0),交点为中点 y 坐标。
+ if dxl != 0:
+ t = (CX - x1) / dxl
+ y_int = y1 + t * dyl
+ inter = (int(CX), int(y_int))
+ else:
+ inter = (int(CX), int((y1 + y2) / 2))
+
+ # NOTE: 通过各种公式计算出角度和偏移亮
+ p_up = (x1, y1) if y1 < y2 else (x2, y2)
+ vx, vy = p_up[0] - inter[0], p_up[1] - inter[1]
+ raw2 = math.atan2(vx, -vy)
+ grd2 = math.asin(math.sin(raw2) * math.cos(tilt))
+ signed = math.degrees(grd2)
+
+ off_px, midpt = offset_after_rotation(line)
+ pts = [
+ np.clip(pt, [0, 0], [depth_mm.shape[1] - 1, depth_mm.shape[0] - 1])
+ for pt in line
+ ]
+ Zs = [float(depth_mm[pt[1], pt[0]]) for pt in pts]
+ Zavg = np.mean([z for z in Zs if z > 0]) if any(z > 0 for z in Zs) else MIN_DEPTH
+ off_mm = off_px * Zavg / FX * math.cos(tilt)
+
+ return signed, off_mm, line, midpt, depth_mm, ROI, inter
+
+
+class TrackDetector:
+ def __init__(self, camera_list, alpha=0.6, win_raw=5, win_smooth=5, interval=0.2):
+ self.alpha, self.interval = alpha, interval
+ self.ang_raw = {sn: deque(maxlen=win_raw) for sn in camera_list}
+ self.off_raw = {sn: deque(maxlen=win_raw) for sn in camera_list}
+ self.ang_smooth = {sn: deque(maxlen=win_smooth) for sn in camera_list}
+ self.off_smooth = {sn: deque(maxlen=win_smooth) for sn in camera_list}
+ self.last_ang = {sn: None for sn in camera_list}
+ self.last_off = {sn: None for sn in camera_list}
+ self.last_t = {sn: 0.0 for sn in camera_list}
+
+ def process(self, depth, sn):
+ # TODO: 先进行对当前时钟判断,如果小于interval则返回空
+ now = cv2.getTickCount() / cv2.getTickFrequency()
+ if now - self.last_t[sn] < self.interval:
+ return None
+
+ self.last_t[sn] = now
+ res = compute_metrics(depth)
+ if res[0] is None:
+ return None
+ ang, off, line, midpt, _, _, inter = res
+
+ # TODO: 平滑
+ self.ang_raw[sn].append(ang)
+ self.off_raw[sn].append(off)
+ med_ang = float(np.median(self.ang_raw[sn]))
+ med_off = float(np.median(self.off_raw[sn]))
+ pa, po = self.last_ang[sn], self.last_off[sn]
+ ang_exp = (
+ med_ang if pa is None else self.alpha * med_ang + (1 - self.alpha) * pa
+ )
+ off_exp = (
+ med_off if po is None else self.alpha * med_off + (1 - self.alpha) * po
+ )
+ self.last_ang[sn], self.last_off[sn] = ang_exp, off_exp
+ self.ang_smooth[sn].append(ang_exp)
+ self.off_smooth[sn].append(off_exp)
+ disp_ang = float(np.median(self.ang_smooth[sn]))
+ disp_off = float(np.median(self.off_smooth[sn]))
+
+ return {
+ "angle": -disp_ang, # 左正右负
+ "offset": disp_off,
+ "line": line,
+ "midpoint": midpt,
+ "intersection": inter,
+ }
diff --git a/lib/camera/ArenaCamera.py b/lib/camera/ArenaCamera.py
new file mode 100644
index 0000000..63e6054
--- /dev/null
+++ b/lib/camera/ArenaCamera.py
@@ -0,0 +1,294 @@
+import ctypes
+import time
+import numpy as np
+import cv2
+
+# 定义错误代码
+ARENA_ACQ_SUCCESS = 0
+
+# 打印错误信息
+def print_error(operation, error):
+ print(f"{operation} failed with error code: {error}")
+
+# 重连机制函数
+def retry_operation(operation_func, handle, *args, max_retries=1, delay=1):
+ """
+ 重试机制函数
+ :param operation_func: 要执行的操作函数
+ :param handle: 相机句柄
+ :param args: 操作函数的参数
+ :param max_retries: 最大重试次数
+ :param delay: 重试间隔时间(秒)
+ :return: 操作结果
+ """
+ for attempt in range(max_retries + 1):
+ err = operation_func(handle, *args)
+ if err == ARENA_ACQ_SUCCESS:
+ return True
+ else:
+ print(f"Attempt {attempt + 1}/{max_retries} failed. Retrying in {delay} seconds...")
+ time.sleep(delay)
+ print_error(operation_func.__name__, err)
+ return False
+
+class ArenaCamera:
+ # 静态变量存储共享库
+ libArenaAcq = ctypes.CDLL('libArenaAcq.so')
+ sys_handle = ctypes.c_void_p()
+ functions_initialized = False # Class-level flag
+
+ def __init__(self, sn):
+ self.sn = sn
+ self.handle = ctypes.c_void_p()
+ self.count = 0
+
+ # Initialize function argument types and return types if not already done
+ if not ArenaCamera.functions_initialized:
+ self._initialize_functions()
+ ArenaCamera.functions_initialized = True
+
+ @classmethod
+ def _initialize_functions(cls):
+ # 定义 ArenaAcq_Initialize
+ cls.libArenaAcq.ArenaAcq_Initialize.argtypes = [ctypes.POINTER(ctypes.c_void_p)]
+ cls.libArenaAcq.ArenaAcq_Initialize.restype = ctypes.c_int
+
+ # 定义 ArenaAcq_Connect
+ cls.libArenaAcq.ArenaAcq_Connect.argtypes = [ctypes.c_void_p, ctypes.POINTER(ctypes.c_void_p),ctypes.c_char_p]
+ cls.libArenaAcq.ArenaAcq_Connect.restype = ctypes.c_int
+
+ # 定义 ArenaAcq_SetProperty
+ cls.libArenaAcq.ArenaAcq_SetProperty.argtypes = [
+ ctypes.c_void_p, ctypes.c_char_p, ctypes.c_char_p
+ ]
+ cls.libArenaAcq.ArenaAcq_SetProperty.restype = ctypes.c_int
+
+ # 定义 ArenaAcq_GetProperty
+ cls.libArenaAcq.ArenaAcq_GetProperty.argtypes = [
+ ctypes.c_void_p, ctypes.c_char_p, ctypes.c_char_p, ctypes.POINTER(ctypes.c_size_t)
+ ]
+ cls.libArenaAcq.ArenaAcq_GetProperty.restype = ctypes.c_int
+
+ # 定义 ArenaAcq_StartAcquisitionStream
+ cls.libArenaAcq.ArenaAcq_StartAcquisitionStream.argtypes = [ctypes.c_void_p]
+ cls.libArenaAcq.ArenaAcq_StartAcquisitionStream.restype = ctypes.c_int
+
+ # 定义 ArenaAcq_GetDepthImage
+ cls.libArenaAcq.ArenaAcq_GetDepthImage.argtypes = [
+ ctypes.c_void_p,
+ ctypes.POINTER(ctypes.POINTER(ctypes.c_uint16)),
+ ctypes.POINTER(ctypes.POINTER(ctypes.c_uint16)),
+ ctypes.POINTER(ctypes.POINTER(ctypes.c_uint16)),
+ ctypes.POINTER(ctypes.c_size_t),
+ ctypes.POINTER(ctypes.c_size_t),
+ ctypes.POINTER(ctypes.c_size_t),
+ ctypes.POINTER(ctypes.c_size_t)
+ ]
+ cls.libArenaAcq.ArenaAcq_GetDepthImage.restype = ctypes.c_int
+
+ # 定义 ArenaAcq_GetImage
+ cls.libArenaAcq.ArenaAcq_GetImage.argtypes = [
+ ctypes.c_void_p,
+ ctypes.POINTER(ctypes.POINTER(ctypes.c_uint16)),
+ ctypes.POINTER(ctypes.c_size_t),
+ ctypes.POINTER(ctypes.c_size_t),
+ ctypes.POINTER(ctypes.c_size_t),
+ ctypes.POINTER(ctypes.c_size_t)
+ ]
+ cls.libArenaAcq.ArenaAcq_GetImage.restype = ctypes.c_int
+
+ # 定义 ArenaAcq_ReleaseImage
+ cls.libArenaAcq.ArenaAcq_ReleaseImage.argtypes = [ctypes.POINTER(ctypes.c_uint8)]
+ cls.libArenaAcq.ArenaAcq_ReleaseImage.restype = ctypes.c_int
+
+ cls.libArenaAcq.ArenaAcq_ReleaseHandle.argtypes = [ctypes.POINTER(ctypes.c_void_p)]
+ cls.libArenaAcq.ArenaAcq_ReleaseHandle.restype = ctypes.c_int
+
+ cls.libArenaAcq.ArenaAcq_ReleaseDevice.argtypes = [ctypes.POINTER(ctypes.c_void_p)]
+ cls.libArenaAcq.ArenaAcq_ReleaseDevice.restype = ctypes.c_int
+
+ # 定义 ArenaAcq_StopAcquisitionStream
+ cls.libArenaAcq.ArenaAcq_StopAcquisitionStream.argtypes = [ctypes.c_void_p]
+ cls.libArenaAcq.ArenaAcq_StopAcquisitionStream.restype = ctypes.c_int
+
+ # 定义 ArenaAcq_Disconnect
+ cls.libArenaAcq.ArenaAcq_Disconnect.argtypes = [ctypes.c_void_p,ctypes.c_void_p]
+ cls.libArenaAcq.ArenaAcq_Disconnect.restype = ctypes.c_int
+
+ # 定义 ArenaAcq_Cleanup
+ cls.libArenaAcq.ArenaAcq_Cleanup.argtypes = [ctypes.c_void_p]
+ cls.libArenaAcq.ArenaAcq_Cleanup.restype = ctypes.c_int
+
+ cls.libArenaAcq.ArenaAcq_SaveDepthImageAsPGM.argtypes = [ctypes.POINTER(ctypes.c_uint16),ctypes.c_size_t,ctypes.c_size_t,ctypes.c_char_p]
+ cls.libArenaAcq.ArenaAcq_SaveDepthImageAsPGM.restype = ctypes.c_int
+
+
+ # 初始化库
+ if not retry_operation(cls.libArenaAcq.ArenaAcq_Initialize, ctypes.byref(cls.sys_handle)):
+ print(f"Initialization failed")
+ cls.libArenaAcq.ArenaAcq_Cleanup(cls.sys_handle)
+ cls.libArenaAcq.ArenaAcq_ReleaseHandle(cls.sys_handle)
+ return
+ print(f"Library initialized successfully")
+
+ @classmethod
+ def shutdown(cls):
+ cls.libArenaAcq.ArenaAcq_Cleanup(cls.sys_handle)
+ print(f"Library shutdown successfully")
+
+
+ def create(self):
+
+ # 连接到相机
+ if not retry_operation(self.libArenaAcq.ArenaAcq_Connect,self.sys_handle, self.handle, self.sn.encode('utf-8')):
+ print(f"Connection failed for camera {self.sn}")
+ self.libArenaAcq.ArenaAcq_Cleanup(self.handle)
+ return
+ print(f"Connected to camera {self.sn} successfully")
+
+ # 开始采集流
+ if not retry_operation(self.libArenaAcq.ArenaAcq_StartAcquisitionStream, self.handle):
+ print(f"Start acquisition failed for camera {self.sn}")
+ self.destroy()
+ return
+ print(f"Acquisition started successfully for camera {self.sn}")
+
+ def destroy(self):
+ # 停止采集流
+ if not retry_operation(self.libArenaAcq.ArenaAcq_StopAcquisitionStream, self.handle):
+ print(f"Stop acquisition failed for camera {self.sn}")
+ self.libArenaAcq.ArenaAcq_Disconnect(self.sys_handle,self.handle)
+ self.libArenaAcq.ArenaAcq_Cleanup(self.handle)
+ return
+ print(f"Acquisition stopped successfully for camera {self.sn}")
+
+ # 断开与相机的连接
+ if not retry_operation(self.libArenaAcq.ArenaAcq_Disconnect,self.sys_handle,self.handle):
+ print(f"Disconnection failed for camera {self.sn}")
+ self.libArenaAcq.ArenaAcq_Cleanup(self.handle)
+ return
+ print(f"Disconnected from camera {self.sn} successfully")
+
+ # 清理资源
+ if not retry_operation(self.libArenaAcq.ArenaAcq_Cleanup, self.handle):
+ print(f"Cleanup failed for camera {self.sn}")
+ return
+
+ def read(self):
+ image_data = ctypes.POINTER(ctypes.c_uint16)()
+
+ image_size = ctypes.c_size_t()
+ width = ctypes.c_size_t()
+ height = ctypes.c_size_t()
+ bits_per_pixel = ctypes.c_size_t()
+
+ if not retry_operation(self.libArenaAcq.ArenaAcq_GetImage, self.handle, ctypes.byref(image_data),
+ ctypes.byref(image_size), ctypes.byref(width), ctypes.byref(height),
+ ctypes.byref(bits_per_pixel)):
+ print(f"Image acquisition failed for camera {self.sn}")
+ return None
+
+ if image_size.value<=0:
+ print(f"Image size is 0 for camera {self.sn}")
+ return None
+
+ # 将图像数据转换为OpenCV格式
+ image_array = ctypes.cast(image_data, ctypes.POINTER(ctypes.c_uint16 * (width.value * height.value))).contents
+
+
+ image_np = np.array(image_array).reshape(height.value, width.value)
+
+ image_np = np.copy(image_np)
+
+ self.count=self.count+1
+
+ # 释放图像资源
+ self.libArenaAcq.ArenaAcq_ReleaseImage(ctypes.cast(image_data, ctypes.POINTER(ctypes.c_uint8)))
+
+ return image_np
+
+ def capture(self):
+ image_data = ctypes.POINTER(ctypes.c_uint16)()
+ x_image_data = ctypes.POINTER(ctypes.c_uint16)()
+ y_image_data = ctypes.POINTER(ctypes.c_uint16)()
+
+ image_size = ctypes.c_size_t()
+ width = ctypes.c_size_t()
+ height = ctypes.c_size_t()
+ bits_per_pixel = ctypes.c_size_t()
+
+ if not retry_operation(self.libArenaAcq.ArenaAcq_GetDepthImage, self.handle, ctypes.byref(image_data),
+ ctypes.byref(x_image_data), ctypes.byref(y_image_data),
+ ctypes.byref(image_size), ctypes.byref(width), ctypes.byref(height),
+ ctypes.byref(bits_per_pixel)):
+ print(f"Image acquisition failed for camera {self.sn}")
+ return None, None, None
+
+ if image_size.value<=0:
+ return None,None,None
+
+ # 将图像数据转换为OpenCV格式
+ depth_image_array = ctypes.cast(image_data, ctypes.POINTER(ctypes.c_uint16 * (width.value * height.value))).contents
+ x_image_array = ctypes.cast(x_image_data, ctypes.POINTER(ctypes.c_uint16 * (width.value * height.value))).contents
+ y_image_array = ctypes.cast(y_image_data, ctypes.POINTER(ctypes.c_uint16 * (width.value * height.value))).contents
+
+
+ depth_image_np = np.array(depth_image_array).reshape(height.value, width.value)
+ x_image_np = np.array(x_image_array).reshape(height.value, width.value)
+ y_image_np = np.array(y_image_array).reshape(height.value, width.value)
+
+ depth_image_np = np.copy(depth_image_np)
+ x_image_np = np.copy(x_image_np)
+ y_image_np = np.copy(y_image_np)
+ # print("copied.")
+
+ # self.libArenaAcq.ArenaAcq_SaveDepthImageAsPGM(image_data,width,height,f'dbg_{self.sn}_{self.count}'.encode('utf-8'))
+ self.count=self.count+1
+
+ # 释放图像资源
+ self.libArenaAcq.ArenaAcq_ReleaseImage(ctypes.cast(image_data, ctypes.POINTER(ctypes.c_uint8)))
+ self.libArenaAcq.ArenaAcq_ReleaseImage(ctypes.cast(x_image_data, ctypes.POINTER(ctypes.c_uint8)))
+ self.libArenaAcq.ArenaAcq_ReleaseImage(ctypes.cast(y_image_data, ctypes.POINTER(ctypes.c_uint8)))
+
+ return x_image_np, y_image_np, depth_image_np
+
+if __name__ == '__main__':
+ cam2 = ArenaCamera("233801341") # Hypothetical second camera serial number
+ cam2.create()
+ cam1 = ArenaCamera("233800056")
+ cam1.create()
+
+ # cv2.namedWindow("Z1",cv2.WINDOW_AUTOSIZE)
+ # cv2.namedWindow("Z2",cv2.WINDOW_AUTOSIZE)
+
+ i=0
+ while i<20:
+ raw1 = cam1.read()
+ X2, Y2, Z2 = cam2.capture()
+ # X1, Y1, Z1 = cam1.capture()
+
+
+ # Display images for the first camera
+ # cv2.imshow("X1", X1)
+ # cv2.imshow("Y1", Y1)
+ # cv2.imshow("Z1", Z1)
+
+ # Display images for the second camera
+ # cv2.imshow("X2", X2)
+ # cv2.imshow("Y2", Y2)
+ # cv2.imshow("Z2", Z2)
+
+ # if cv2.waitKey(0) & 0xFF == ord('q'):
+ # break
+ # cv2.imwrite("z1.png",Z1)
+ cv2.imwrite("z2.png",Z2)
+ # time.sleep(3)
+ i=i+1
+ cv2.imwrite("raw1.png",raw1)
+ print(f'read {i}')
+
+
+ cv2.destroyAllWindows()
+ cam1.destroy()
+ cam2.destroy()
+ ArenaCamera.shutdown()
\ No newline at end of file
diff --git a/lib/camera/MindVisionCamera.py b/lib/camera/MindVisionCamera.py
new file mode 100644
index 0000000..690ac93
--- /dev/null
+++ b/lib/camera/MindVisionCamera.py
@@ -0,0 +1,153 @@
+import sys
+import platform
+from PySide6.QtWidgets import QApplication, QMainWindow, QLabel
+from PySide6.QtCore import Qt
+from PySide6.QtGui import QImage, QPixmap
+from PySide6.QtCore import QTimer
+import numpy as np
+import ctypes
+from lib.camera.mvsdk import *
+from lib.camera import mvsdk
+
+
+class MindVisionCamera:
+ def __init__(self, sn):
+ self.sn = sn # 相机序列号
+ self.hCamera = None # 相机句柄
+ self.FrameBufferSize = None # 帧缓冲区大小
+ self.pFrameBuffer = None # 帧缓冲区指针
+ self.monoCamera = None # 是否为单色相机标志
+ self.cap = None # 相机能力参数
+
+ # Initialize camera
+ self._initialize_camera()
+
+ def _initialize_camera(self):
+ # Enumerate cameras
+ DevList = CameraEnumerateDevice()
+ nDev = len(DevList)
+ if nDev < 1:
+ print("No camera was found!")
+ return
+
+ for i, DevInfo in enumerate(DevList):
+ # 检索指定sn相机
+ if DevInfo.GetSn() == self.sn:
+ print(f"Found camera with SN: {self.sn}")
+ break
+ else:
+ print(f"Camera with SN: {self.sn} not found!")
+ return
+
+ # Open camera
+ try:
+ self.hCamera = CameraInit(DevInfo, -1, -1)
+ except CameraException as e:
+ print("CameraInit Failed({}): {}".format(e.error_code, e.message))
+ return
+ # 获取相机参数
+ self.cap = CameraGetCapability(self.hCamera)
+ # 判断是否为单色相机
+ self.monoCamera = self.cap.sIspCapacity.bMonoSensor != 0
+
+ if self.monoCamera:
+ CameraSetIspOutFormat(self.hCamera, CAMERA_MEDIA_TYPE_MONO8)
+
+ CameraSetTriggerMode(self.hCamera, 0) # 设置触发模式为连续采集
+ CameraSetAeState(self.hCamera, 1) # 关闭自动曝光
+ # CameraSetExposureTime(self.hCamera, 30 * 1000) # 设置曝光时间为30ms
+ CameraPlay(self.hCamera) # 开始采集
+
+ # 分配帧缓冲区
+ self.FrameBufferSize = (
+ self.cap.sResolutionRange.iWidthMax
+ * self.cap.sResolutionRange.iHeightMax
+ * (1 if self.monoCamera else 3)
+ )
+ self.pFrameBuffer = CameraAlignMalloc(self.FrameBufferSize, 16)
+
+ def capture(self):
+ try:
+ # 从相机获取图像数据,2000ms超时,返回原始数据指针和帧头信息
+ pRawData, FrameHead = CameraGetImageBuffer(self.hCamera, 2000)
+ CameraImageProcess(self.hCamera, pRawData, self.pFrameBuffer, FrameHead)
+ # 反转
+ if platform.system() == "Windows":
+ mvsdk.CameraFlipFrameBuffer(self.pFrameBuffer, FrameHead, 1)
+ # 此时图片已经存储在pFrameBuffer中, 对于彩色相机pFrameBuffer=RGB数据, 黑白相机pFrameBuffer=8位灰度数据
+ # 将图像数据转换为OpenCV格式
+ image_array = (mvsdk.c_ubyte * FrameHead.uBytes).from_address(
+ self.pFrameBuffer
+ )
+
+ if self.monoCamera:
+ image_np = np.array(image_array).reshape(
+ FrameHead.iHeight, FrameHead.iWidth
+ )
+ else:
+ image_np = np.array(image_array).reshape(
+ FrameHead.iHeight, FrameHead.iWidth, 3
+ )
+ # Convert to OpenCV format
+ if FrameHead.uiMediaType == CAMERA_MEDIA_TYPE_MONO8:
+ image = np.frombuffer(image_np, dtype=np.uint8).reshape(
+ FrameHead.iHeight, FrameHead.iWidth
+ )
+ else:
+ image = np.frombuffer(image_np, dtype=np.uint8).reshape(
+ FrameHead.iHeight, FrameHead.iWidth, 3
+ )
+
+ CameraReleaseImageBuffer(self.hCamera, pRawData)
+ return image
+
+ except CameraException as e:
+ print("CameraGetImageBuffer failed({}): {}".format(e.error_code, e.message))
+ return None
+
+ def __del__(self):
+ if self.hCamera:
+ CameraUnInit(self.hCamera)
+ if self.pFrameBuffer:
+ CameraAlignFree(self.pFrameBuffer)
+
+
+# class MainWindow(QMainWindow):
+# def __init__(self, camera):
+# super().__init__()
+# self.setWindowTitle("MindVision Camera")
+# self.setGeometry(100, 100, 800, 600)
+# self.label = QLabel(self)
+# self.label.setAlignment(Qt.AlignCenter)
+# self.label.setScaledContents(True) # 自动缩放图像以适应标签大小
+# self.camera = camera
+# self.timer = QTimer(self)
+# self.timer.timeout.connect(self.update_frame)
+# self.timer.start(30) # Update frame every 30ms
+
+# def closeEvent(self, event):
+# self.timer.stop()
+# self.camera.__del__()
+# event.accept()
+
+# def resizeEvent(self, event):
+# super().resizeEvent(event)
+# self.update_frame() # 窗口大小改变时更新图像
+
+# def update_frame(self):
+# image = self.camera.capture()
+# if image is not None:
+# if self.camera.monoCamera:
+# qimage = QImage(image.data, image.shape[1], image.shape[0], QImage.Format_Grayscale8)
+# else:
+# qimage = QImage(image.data, image.shape[1], image.shape[0], QImage.Format_BGR888)
+# pixmap = QPixmap.fromImage(qimage)
+# self.label.setPixmap(pixmap)
+# self.label.resize(self.size()) # 调整标签大小以适应窗口
+
+# if __name__ == '__main__':
+# app = QApplication(sys.argv)
+# cam = MindVisionCamera("054042423002")
+# window = MainWindow(cam)
+# window.show()
+# sys.exit(app.exec())
diff --git a/lib/camera/__init__.py b/lib/camera/__init__.py
new file mode 100644
index 0000000..e69de29
diff --git a/lib/camera/mvsdk.py b/lib/camera/mvsdk.py
new file mode 100644
index 0000000..460915f
--- /dev/null
+++ b/lib/camera/mvsdk.py
@@ -0,0 +1,2394 @@
+#coding=utf-8
+import platform
+from ctypes import *
+from threading import local
+
+# 回调函数类型
+CALLBACK_FUNC_TYPE = None
+
+# SDK动态库
+_sdk = None
+
+def _Init():
+ global _sdk
+ global CALLBACK_FUNC_TYPE
+
+ is_win = (platform.system() == "Windows")
+ is_x86 = (platform.architecture()[0] == '32bit')
+
+ if is_win:
+ _sdk = windll.MVCAMSDK if is_x86 else windll.MVCAMSDK_X64
+ CALLBACK_FUNC_TYPE = WINFUNCTYPE
+ else:
+ _sdk = cdll.LoadLibrary("libMVSDK.so")
+ CALLBACK_FUNC_TYPE = CFUNCTYPE
+
+_Init()
+
+#-------------------------------------------类型定义--------------------------------------------------
+
+# 状态码定义
+CAMERA_STATUS_SUCCESS = 0 # 操作成功
+CAMERA_STATUS_FAILED = -1 # 操作失败
+CAMERA_STATUS_INTERNAL_ERROR = -2 # 内部错误
+CAMERA_STATUS_UNKNOW = -3 # 未知错误
+CAMERA_STATUS_NOT_SUPPORTED = -4 # 不支持该功能
+CAMERA_STATUS_NOT_INITIALIZED = -5 # 初始化未完成
+CAMERA_STATUS_PARAMETER_INVALID = -6 # 参数无效
+CAMERA_STATUS_PARAMETER_OUT_OF_BOUND = -7 # 参数越界
+CAMERA_STATUS_UNENABLED = -8 # 未使能
+CAMERA_STATUS_USER_CANCEL = -9 # 用户手动取消了,比如roi面板点击取消,返回
+CAMERA_STATUS_PATH_NOT_FOUND = -10 # 注册表中没有找到对应的路径
+CAMERA_STATUS_SIZE_DISMATCH = -11 # 获得图像数据长度和定义的尺寸不匹配
+CAMERA_STATUS_TIME_OUT = -12 # 超时错误
+CAMERA_STATUS_IO_ERROR = -13 # 硬件IO错误
+CAMERA_STATUS_COMM_ERROR = -14 # 通讯错误
+CAMERA_STATUS_BUS_ERROR = -15 # 总线错误
+CAMERA_STATUS_NO_DEVICE_FOUND = -16 # 没有发现设备
+CAMERA_STATUS_NO_LOGIC_DEVICE_FOUND = -17 # 未找到逻辑设备
+CAMERA_STATUS_DEVICE_IS_OPENED = -18 # 设备已经打开
+CAMERA_STATUS_DEVICE_IS_CLOSED = -19 # 设备已经关闭
+CAMERA_STATUS_DEVICE_VEDIO_CLOSED = -20 # 没有打开设备视频,调用录像相关的函数时,如果相机视频没有打开,则回返回该错误。
+CAMERA_STATUS_NO_MEMORY = -21 # 没有足够系统内存
+CAMERA_STATUS_FILE_CREATE_FAILED = -22 # 创建文件失败
+CAMERA_STATUS_FILE_INVALID = -23 # 文件格式无效
+CAMERA_STATUS_WRITE_PROTECTED = -24 # 写保护,不可写
+CAMERA_STATUS_GRAB_FAILED = -25 # 数据采集失败
+CAMERA_STATUS_LOST_DATA = -26 # 数据丢失,不完整
+CAMERA_STATUS_EOF_ERROR = -27 # 未接收到帧结束符
+CAMERA_STATUS_BUSY = -28 # 正忙(上一次操作还在进行中),此次操作不能进行
+CAMERA_STATUS_WAIT = -29 # 需要等待(进行操作的条件不成立),可以再次尝试
+CAMERA_STATUS_IN_PROCESS = -30 # 正在进行,已经被操作过
+CAMERA_STATUS_IIC_ERROR = -31 # IIC传输错误
+CAMERA_STATUS_SPI_ERROR = -32 # SPI传输错误
+CAMERA_STATUS_USB_CONTROL_ERROR = -33 # USB控制传输错误
+CAMERA_STATUS_USB_BULK_ERROR = -34 # USB BULK传输错误
+CAMERA_STATUS_SOCKET_INIT_ERROR = -35 # 网络传输套件初始化失败
+CAMERA_STATUS_GIGE_FILTER_INIT_ERROR = -36 # 网络相机内核过滤驱动初始化失败,请检查是否正确安装了驱动,或者重新安装。
+CAMERA_STATUS_NET_SEND_ERROR = -37 # 网络数据发送错误
+CAMERA_STATUS_DEVICE_LOST = -38 # 与网络相机失去连接,心跳检测超时
+CAMERA_STATUS_DATA_RECV_LESS = -39 # 接收到的字节数比请求的少
+CAMERA_STATUS_FUNCTION_LOAD_FAILED = -40 # 从文件中加载程序失败
+CAMERA_STATUS_CRITICAL_FILE_LOST = -41 # 程序运行所必须的文件丢失。
+CAMERA_STATUS_SENSOR_ID_DISMATCH = -42 # 固件和程序不匹配,原因是下载了错误的固件。
+CAMERA_STATUS_OUT_OF_RANGE = -43 # 参数超出有效范围。
+CAMERA_STATUS_REGISTRY_ERROR = -44 # 安装程序注册错误。请重新安装程序,或者运行安装目录Setup/Installer.exe
+CAMERA_STATUS_ACCESS_DENY = -45 # 禁止访问。指定相机已经被其他程序占用时,再申请访问该相机,会返回该状态。(一个相机不能被多个程序同时访问)
+#AIA的标准兼容的错误码
+CAMERA_AIA_PACKET_RESEND = 0x0100 #该帧需要重传
+CAMERA_AIA_NOT_IMPLEMENTED = 0x8001 #设备不支持的命令
+CAMERA_AIA_INVALID_PARAMETER = 0x8002 #命令参数非法
+CAMERA_AIA_INVALID_ADDRESS = 0x8003 #不可访问的地址
+CAMERA_AIA_WRITE_PROTECT = 0x8004 #访问的对象不可写
+CAMERA_AIA_BAD_ALIGNMENT = 0x8005 #访问的地址没有按照要求对齐
+CAMERA_AIA_ACCESS_DENIED = 0x8006 #没有访问权限
+CAMERA_AIA_BUSY = 0x8007 #命令正在处理中
+CAMERA_AIA_DEPRECATED = 0x8008 #0x8008-0x0800B 0x800F 该指令已经废弃
+CAMERA_AIA_PACKET_UNAVAILABLE = 0x800C #包无效
+CAMERA_AIA_DATA_OVERRUN = 0x800D #数据溢出,通常是收到的数据比需要的多
+CAMERA_AIA_INVALID_HEADER = 0x800E #数据包头部中某些区域与协议不匹配
+CAMERA_AIA_PACKET_NOT_YET_AVAILABLE = 0x8010 #图像分包数据还未准备好,多用于触发模式,应用程序访问超时
+CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY = 0x8011 #需要访问的分包已经不存在。多用于重传时数据已经不在缓冲区中
+CAMERA_AIA_PACKET_REMOVED_FROM_MEMORY = 0x8012 #CAMERA_AIA_PACKET_AND_PREV_REMOVED_FROM_MEMORY
+CAMERA_AIA_NO_REF_TIME = 0x0813 #没有参考时钟源。多用于时间同步的命令执行时
+CAMERA_AIA_PACKET_TEMPORARILY_UNAVAILABLE = 0x0814 #由于信道带宽问题,当前分包暂时不可用,需稍后进行访问
+CAMERA_AIA_OVERFLOW = 0x0815 #设备端数据溢出,通常是队列已满
+CAMERA_AIA_ACTION_LATE = 0x0816 #命令执行已经超过有效的指定时间
+CAMERA_AIA_ERROR = 0x8FFF #错误
+
+# 图像格式定义
+CAMERA_MEDIA_TYPE_MONO = 0x01000000
+CAMERA_MEDIA_TYPE_RGB = 0x02000000
+CAMERA_MEDIA_TYPE_COLOR = 0x02000000
+CAMERA_MEDIA_TYPE_OCCUPY1BIT = 0x00010000
+CAMERA_MEDIA_TYPE_OCCUPY2BIT = 0x00020000
+CAMERA_MEDIA_TYPE_OCCUPY4BIT = 0x00040000
+CAMERA_MEDIA_TYPE_OCCUPY8BIT = 0x00080000
+CAMERA_MEDIA_TYPE_OCCUPY10BIT = 0x000A0000
+CAMERA_MEDIA_TYPE_OCCUPY12BIT = 0x000C0000
+CAMERA_MEDIA_TYPE_OCCUPY16BIT = 0x00100000
+CAMERA_MEDIA_TYPE_OCCUPY24BIT = 0x00180000
+CAMERA_MEDIA_TYPE_OCCUPY32BIT = 0x00200000
+CAMERA_MEDIA_TYPE_OCCUPY36BIT = 0x00240000
+CAMERA_MEDIA_TYPE_OCCUPY48BIT = 0x00300000
+CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_MASK = 0x00FF0000
+CAMERA_MEDIA_TYPE_EFFECTIVE_PIXEL_SIZE_SHIFT = 16
+CAMERA_MEDIA_TYPE_ID_MASK = 0x0000FFFF
+CAMERA_MEDIA_TYPE_COUNT = 0x46
+
+#mono
+CAMERA_MEDIA_TYPE_MONO1P = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY1BIT | 0x0037)
+CAMERA_MEDIA_TYPE_MONO2P = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY2BIT | 0x0038)
+CAMERA_MEDIA_TYPE_MONO4P = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY4BIT | 0x0039)
+CAMERA_MEDIA_TYPE_MONO8 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0001)
+CAMERA_MEDIA_TYPE_MONO8S = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0002)
+CAMERA_MEDIA_TYPE_MONO10 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0003)
+CAMERA_MEDIA_TYPE_MONO10_PACKED = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0004)
+CAMERA_MEDIA_TYPE_MONO12 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0005)
+CAMERA_MEDIA_TYPE_MONO12_PACKED = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0006)
+CAMERA_MEDIA_TYPE_MONO14 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0025)
+CAMERA_MEDIA_TYPE_MONO16 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0007)
+
+# Bayer
+CAMERA_MEDIA_TYPE_BAYGR8 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0008)
+CAMERA_MEDIA_TYPE_BAYRG8 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x0009)
+CAMERA_MEDIA_TYPE_BAYGB8 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x000A)
+CAMERA_MEDIA_TYPE_BAYBG8 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY8BIT | 0x000B)
+
+CAMERA_MEDIA_TYPE_BAYGR10_MIPI = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0026)
+CAMERA_MEDIA_TYPE_BAYRG10_MIPI = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0027)
+CAMERA_MEDIA_TYPE_BAYGB10_MIPI = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0028)
+CAMERA_MEDIA_TYPE_BAYBG10_MIPI = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY10BIT | 0x0029)
+
+CAMERA_MEDIA_TYPE_BAYGR10 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000C)
+CAMERA_MEDIA_TYPE_BAYRG10 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000D)
+CAMERA_MEDIA_TYPE_BAYGB10 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000E)
+CAMERA_MEDIA_TYPE_BAYBG10 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x000F)
+
+CAMERA_MEDIA_TYPE_BAYGR12 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0010)
+CAMERA_MEDIA_TYPE_BAYRG12 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0011)
+CAMERA_MEDIA_TYPE_BAYGB12 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0012)
+CAMERA_MEDIA_TYPE_BAYBG12 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0013)
+
+CAMERA_MEDIA_TYPE_BAYGR10_PACKED = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0026)
+CAMERA_MEDIA_TYPE_BAYRG10_PACKED = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0027)
+CAMERA_MEDIA_TYPE_BAYGB10_PACKED = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0028)
+CAMERA_MEDIA_TYPE_BAYBG10_PACKED = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0029)
+
+CAMERA_MEDIA_TYPE_BAYGR12_PACKED = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002A)
+CAMERA_MEDIA_TYPE_BAYRG12_PACKED = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002B)
+CAMERA_MEDIA_TYPE_BAYGB12_PACKED = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002C)
+CAMERA_MEDIA_TYPE_BAYBG12_PACKED = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x002D)
+
+CAMERA_MEDIA_TYPE_BAYGR16 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x002E)
+CAMERA_MEDIA_TYPE_BAYRG16 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x002F)
+CAMERA_MEDIA_TYPE_BAYGB16 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0030)
+CAMERA_MEDIA_TYPE_BAYBG16 = (CAMERA_MEDIA_TYPE_MONO | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0031)
+
+# RGB
+CAMERA_MEDIA_TYPE_RGB8 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0014)
+CAMERA_MEDIA_TYPE_BGR8 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0015)
+CAMERA_MEDIA_TYPE_RGBA8 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x0016)
+CAMERA_MEDIA_TYPE_BGRA8 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x0017)
+CAMERA_MEDIA_TYPE_RGB10 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0018)
+CAMERA_MEDIA_TYPE_BGR10 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0019)
+CAMERA_MEDIA_TYPE_RGB12 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x001A)
+CAMERA_MEDIA_TYPE_BGR12 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x001B)
+CAMERA_MEDIA_TYPE_RGB16 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0033)
+CAMERA_MEDIA_TYPE_RGB10V1_PACKED = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x001C)
+CAMERA_MEDIA_TYPE_RGB10P32 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY32BIT | 0x001D)
+CAMERA_MEDIA_TYPE_RGB12V1_PACKED = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY36BIT | 0X0034)
+CAMERA_MEDIA_TYPE_RGB565P = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0035)
+CAMERA_MEDIA_TYPE_BGR565P = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0X0036)
+
+# YUV and YCbCr
+CAMERA_MEDIA_TYPE_YUV411_8_UYYVYY = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x001E)
+CAMERA_MEDIA_TYPE_YUV422_8_UYVY = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x001F)
+CAMERA_MEDIA_TYPE_YUV422_8 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0032)
+CAMERA_MEDIA_TYPE_YUV8_UYV = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0020)
+CAMERA_MEDIA_TYPE_YCBCR8_CBYCR = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x003A)
+#CAMERA_MEDIA_TYPE_YCBCR422_8 : YYYYCbCrCbCr
+CAMERA_MEDIA_TYPE_YCBCR422_8 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x003B)
+CAMERA_MEDIA_TYPE_YCBCR422_8_CBYCRY = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0043)
+CAMERA_MEDIA_TYPE_YCBCR411_8_CBYYCRYY = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x003C)
+CAMERA_MEDIA_TYPE_YCBCR601_8_CBYCR = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x003D)
+CAMERA_MEDIA_TYPE_YCBCR601_422_8 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x003E)
+CAMERA_MEDIA_TYPE_YCBCR601_422_8_CBYCRY = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0044)
+CAMERA_MEDIA_TYPE_YCBCR601_411_8_CBYYCRYY = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x003F)
+CAMERA_MEDIA_TYPE_YCBCR709_8_CBYCR = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0040)
+CAMERA_MEDIA_TYPE_YCBCR709_422_8 = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0041)
+CAMERA_MEDIA_TYPE_YCBCR709_422_8_CBYCRY = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY16BIT | 0x0045)
+CAMERA_MEDIA_TYPE_YCBCR709_411_8_CBYYCRYY = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY12BIT | 0x0042)
+
+# RGB Planar
+CAMERA_MEDIA_TYPE_RGB8_PLANAR = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY24BIT | 0x0021)
+CAMERA_MEDIA_TYPE_RGB10_PLANAR = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0022)
+CAMERA_MEDIA_TYPE_RGB12_PLANAR = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0023)
+CAMERA_MEDIA_TYPE_RGB16_PLANAR = (CAMERA_MEDIA_TYPE_COLOR | CAMERA_MEDIA_TYPE_OCCUPY48BIT | 0x0024)
+
+# 保存格式
+FILE_JPG = 1
+FILE_BMP = 2
+FILE_RAW = 4
+FILE_PNG = 8
+FILE_BMP_8BIT = 16
+FILE_PNG_8BIT = 32
+FILE_RAW_16BIT = 64
+
+# 触发信号
+EXT_TRIG_LEADING_EDGE = 0
+EXT_TRIG_TRAILING_EDGE = 1
+EXT_TRIG_HIGH_LEVEL = 2
+EXT_TRIG_LOW_LEVEL = 3
+EXT_TRIG_DOUBLE_EDGE = 4
+
+# IO模式
+IOMODE_TRIG_INPUT = 0
+IOMODE_STROBE_OUTPUT = 1
+IOMODE_GP_INPUT = 2
+IOMODE_GP_OUTPUT = 3
+IOMODE_PWM_OUTPUT = 4
+
+
+# 相机操作异常信息
+class CameraException(Exception):
+ """docstring for CameraException"""
+ def __init__(self, error_code):
+ super(CameraException, self).__init__()
+ self.error_code = error_code
+ self.message = CameraGetErrorString(error_code)
+
+ def __str__(self):
+ return 'error_code:{} message:{}'.format(self.error_code, self.message)
+
+class MvStructure(Structure):
+ def __str__(self):
+ strs = []
+ for field in self._fields_:
+ name = field[0]
+ value = getattr(self, name)
+ if isinstance(value, type(b'')):
+ value = _string_buffer_to_str(value)
+ strs.append("{}:{}".format(name, value))
+ return '\n'.join(strs)
+
+ def __repr__(self):
+ return self.__str__()
+
+ def clone(self):
+ obj = type(self)()
+ memmove(byref(obj), byref(self), sizeof(self))
+ return obj
+
+# 相机的设备信息,只读信息,请勿修改
+class tSdkCameraDevInfo(MvStructure):
+ _fields_ = [("acProductSeries", c_char * 32), #产品系列
+ ("acProductName", c_char * 32), #产品名称
+ ("acFriendlyName", c_char * 32), #产品昵称
+ ("acLinkName", c_char * 32), #内核符号连接名,内部使用
+ ("acDriverVersion", c_char * 32), #驱动版本
+ ("acSensorType", c_char * 32), #sensor类型
+ ("acPortType", c_char * 32), #接口类型
+ ("acSn", c_char * 32), #产品唯一序列号
+ ("uInstance", c_uint)] #该型号相机在该电脑上的实例索引号,用于区分同型号多相机
+
+ def GetProductSeries(self):
+ return _string_buffer_to_str(self.acProductSeries)
+ def GetProductName(self):
+ return _string_buffer_to_str(self.acProductName)
+ def GetFriendlyName(self):
+ return _string_buffer_to_str(self.acFriendlyName)
+ def GetLinkName(self):
+ return _string_buffer_to_str(self.acLinkName)
+ def GetDriverVersion(self):
+ return _string_buffer_to_str(self.acDriverVersion)
+ def GetSensorType(self):
+ return _string_buffer_to_str(self.acSensorType)
+ def GetPortType(self):
+ return _string_buffer_to_str(self.acPortType)
+ def GetSn(self):
+ return _string_buffer_to_str(self.acSn)
+
+# 相机的分辨率设定范围
+class tSdkResolutionRange(MvStructure):
+ _fields_ = [("iHeightMax", c_int), #图像最大高度
+ ("iHeightMin", c_int), #图像最小高度
+ ("iWidthMax", c_int), #图像最大宽度
+ ("iWidthMin", c_int), #图像最小宽度
+ ("uSkipModeMask", c_uint), #SKIP模式掩码,为0,表示不支持SKIP 。bit0为1,表示支持SKIP 2x2 bit1为1,表示支持SKIP 3x3....
+ ("uBinSumModeMask", c_uint), #BIN(求和)模式掩码,为0,表示不支持BIN 。bit0为1,表示支持BIN 2x2 bit1为1,表示支持BIN 3x3....
+ ("uBinAverageModeMask", c_uint),#BIN(求均值)模式掩码,为0,表示不支持BIN 。bit0为1,表示支持BIN 2x2 bit1为1,表示支持BIN 3x3....
+ ("uResampleMask", c_uint)] #硬件重采样的掩码
+
+#相机的分辨率描述
+class tSdkImageResolution(MvStructure):
+ _fields_ = [
+ ("iIndex", c_int), # 索引号,[0,N]表示预设的分辨率(N 为预设分辨率的最大个数,一般不超过20),OXFF 表示自定义分辨率(ROI)
+ ("acDescription", c_char * 32), # 该分辨率的描述信息。仅预设分辨率时该信息有效。自定义分辨率可忽略该信息
+ ("uBinSumMode", c_uint), # BIN(求和)的模式,范围不能超过tSdkResolutionRange中uBinSumModeMask
+ ("uBinAverageMode", c_uint), # BIN(求均值)的模式,范围不能超过tSdkResolutionRange中uBinAverageModeMask
+ ("uSkipMode", c_uint), # 是否SKIP的尺寸,为0表示禁止SKIP模式,范围不能超过tSdkResolutionRange中uSkipModeMask
+ ("uResampleMask", c_uint), # 硬件重采样的掩码
+ ("iHOffsetFOV", c_int), # 采集视场相对于Sensor最大视场左上角的垂直偏移
+ ("iVOffsetFOV", c_int), # 采集视场相对于Sensor最大视场左上角的水平偏移
+ ("iWidthFOV", c_int), # 采集视场的宽度
+ ("iHeightFOV", c_int), # 采集视场的高度
+ ("iWidth", c_int), # 相机最终输出的图像的宽度
+ ("iHeight", c_int), # 相机最终输出的图像的高度
+ ("iWidthZoomHd", c_int), # 硬件缩放的宽度,不需要进行此操作的分辨率,此变量设置为0.
+ ("iHeightZoomHd", c_int), # 硬件缩放的高度,不需要进行此操作的分辨率,此变量设置为0.
+ ("iWidthZoomSw", c_int), # 软件缩放的宽度,不需要进行此操作的分辨率,此变量设置为0.
+ ("iHeightZoomSw", c_int), # 软件缩放的高度,不需要进行此操作的分辨率,此变量设置为0.
+ ]
+
+ def GetDescription(self):
+ return _string_buffer_to_str(self.acDescription)
+
+#相机白平衡模式描述信息
+class tSdkColorTemperatureDes(MvStructure):
+ _fields_ = [
+ ("iIndex", c_int), # 模式索引号
+ ("acDescription", c_char * 32), # 描述信息
+ ]
+
+ def GetDescription(self):
+ return _string_buffer_to_str(self.acDescription)
+
+#相机帧率描述信息
+class tSdkFrameSpeed(MvStructure):
+ _fields_ = [
+ ("iIndex", c_int), # 帧率索引号,一般0对应于低速模式,1对应于普通模式,2对应于高速模式
+ ("acDescription", c_char * 32), # 描述信息
+ ]
+
+ def GetDescription(self):
+ return _string_buffer_to_str(self.acDescription)
+
+#相机曝光功能范围定义
+class tSdkExpose(MvStructure):
+ _fields_ = [
+ ("uiTargetMin", c_uint), #自动曝光亮度目标最小值
+ ("uiTargetMax", c_uint), #自动曝光亮度目标最大值
+ ("uiAnalogGainMin", c_uint), #模拟增益的最小值,单位为fAnalogGainStep中定义
+ ("uiAnalogGainMax", c_uint), #模拟增益的最大值,单位为fAnalogGainStep中定义
+ ("fAnalogGainStep", c_float), #模拟增益每增加1,对应的增加的放大倍数。例如,uiAnalogGainMin一般为16,fAnalogGainStep一般为0.125,那么最小放大倍数就是16*0.125 = 2倍
+ ("uiExposeTimeMin", c_uint), #手动模式下,曝光时间的最小值,单位:行。根据CameraGetExposureLineTime可以获得一行对应的时间(微秒),从而得到整帧的曝光时间
+ ("uiExposeTimeMax", c_uint), #手动模式下,曝光时间的最大值,单位:行
+ ]
+
+#触发模式描述
+class tSdkTrigger(MvStructure):
+ _fields_ = [
+ ("iIndex", c_int), # 模式索引号
+ ("acDescription", c_char * 32), # 描述信息
+ ]
+
+ def GetDescription(self):
+ return _string_buffer_to_str(self.acDescription)
+
+#传输分包大小描述(主要是针对网络相机有效)
+class tSdkPackLength(MvStructure):
+ _fields_ = [
+ ("iIndex", c_int), # 模式索引号
+ ("acDescription", c_char * 32), # 描述信息
+ ("iPackSize", c_uint),
+ ]
+
+ def GetDescription(self):
+ return _string_buffer_to_str(self.acDescription)
+
+#预设的LUT表描述
+class tSdkPresetLut(MvStructure):
+ _fields_ = [
+ ("iIndex", c_int), # 编号
+ ("acDescription", c_char * 32), # 描述信息
+ ]
+
+ def GetDescription(self):
+ return _string_buffer_to_str(self.acDescription)
+
+#AE算法描述
+class tSdkAeAlgorithm(MvStructure):
+ _fields_ = [
+ ("iIndex", c_int), # 编号
+ ("acDescription", c_char * 32), # 描述信息
+ ]
+
+ def GetDescription(self):
+ return _string_buffer_to_str(self.acDescription)
+
+#RAW转RGB算法描述
+class tSdkBayerDecodeAlgorithm(MvStructure):
+ _fields_ = [
+ ("iIndex", c_int), # 编号
+ ("acDescription", c_char * 32), # 描述信息
+ ]
+
+ def GetDescription(self):
+ return _string_buffer_to_str(self.acDescription)
+
+#帧率统计信息
+class tSdkFrameStatistic(MvStructure):
+ _fields_ = [
+ ("iTotal", c_int), #当前采集的总帧数(包括错误帧)
+ ("iCapture", c_int), #当前采集的有效帧的数量
+ ("iLost", c_int), #当前丢帧的数量
+ ]
+
+#相机输出的图像数据格式
+class tSdkMediaType(MvStructure):
+ _fields_ = [
+ ("iIndex", c_int), # 格式种类编号
+ ("acDescription", c_char * 32), # 描述信息
+ ("iMediaType", c_uint), # 对应的图像格式编码,如CAMERA_MEDIA_TYPE_BAYGR8。
+ ]
+
+ def GetDescription(self):
+ return _string_buffer_to_str(self.acDescription)
+
+#伽马的设定范围
+class tGammaRange(MvStructure):
+ _fields_ = [
+ ("iMin", c_int), #最小值
+ ("iMax", c_int), #最大值
+ ]
+
+#对比度的设定范围
+class tContrastRange(MvStructure):
+ _fields_ = [
+ ("iMin", c_int), #最小值
+ ("iMax", c_int), #最大值
+ ]
+
+#RGB三通道数字增益的设定范围
+class tRgbGainRange(MvStructure):
+ _fields_ = [
+ ("iRGainMin", c_int), #红色增益的最小值
+ ("iRGainMax", c_int), #红色增益的最大值
+ ("iGGainMin", c_int), #绿色增益的最小值
+ ("iGGainMax", c_int), #绿色增益的最大值
+ ("iBGainMin", c_int), #蓝色增益的最小值
+ ("iBGainMax", c_int), #蓝色增益的最大值
+ ]
+
+#饱和度设定的范围
+class tSaturationRange(MvStructure):
+ _fields_ = [
+ ("iMin", c_int), #最小值
+ ("iMax", c_int), #最大值
+ ]
+
+#锐化的设定范围
+class tSharpnessRange(MvStructure):
+ _fields_ = [
+ ("iMin", c_int), #最小值
+ ("iMax", c_int), #最大值
+ ]
+
+#ISP模块的使能信息
+class tSdkIspCapacity(MvStructure):
+ _fields_ = [
+ ("bMonoSensor", c_int), #表示该型号相机是否为黑白相机,如果是黑白相机,则颜色相关的功能都无法调节
+ ("bWbOnce", c_int), #表示该型号相机是否支持手动白平衡功能
+ ("bAutoWb", c_int), #表示该型号相机是否支持自动白平衡功能
+ ("bAutoExposure", c_int), #表示该型号相机是否支持自动曝光功能
+ ("bManualExposure", c_int), #表示该型号相机是否支持手动曝光功能
+ ("bAntiFlick", c_int), #表示该型号相机是否支持抗频闪功能
+ ("bDeviceIsp", c_int), #表示该型号相机是否支持硬件ISP功能
+ ("bForceUseDeviceIsp", c_int), #bDeviceIsp和bForceUseDeviceIsp同时为TRUE时,表示强制只用硬件ISP,不可取消。
+ ("bZoomHD", c_int), #相机硬件是否支持图像缩放输出(只能是缩小)。
+ ]
+
+# 定义整合的设备描述信息,这些信息可以用于动态构建UI
+class tSdkCameraCapbility(MvStructure):
+ _fields_ = [
+ ("pTriggerDesc", POINTER(tSdkTrigger)),
+ ("iTriggerDesc", c_int), #触发模式的个数,即pTriggerDesc数组的大小
+ ("pImageSizeDesc", POINTER(tSdkImageResolution)),
+ ("iImageSizeDesc", c_int), #预设分辨率的个数,即pImageSizeDesc数组的大小
+ ("pClrTempDesc", POINTER(tSdkColorTemperatureDes)),
+ ("iClrTempDesc", c_int), #预设色温个数
+ ("pMediaTypeDesc", POINTER(tSdkMediaType)),
+ ("iMediaTypeDesc", c_int), #相机输出图像格式的种类个数,即pMediaTypeDesc数组的大小。
+ ("pFrameSpeedDesc", POINTER(tSdkFrameSpeed)), #可调节帧速类型,对应界面上普通 高速 和超级三种速度设置
+ ("iFrameSpeedDesc", c_int), #可调节帧速类型的个数,即pFrameSpeedDesc数组的大小。
+ ("pPackLenDesc", POINTER(tSdkPackLength)), #传输包长度,一般用于网络设备
+ ("iPackLenDesc", c_int), #可供选择的传输分包长度的个数,即pPackLenDesc数组的大小。
+ ("iOutputIoCounts", c_int), #可编程输出IO的个数
+ ("iInputIoCounts", c_int), #可编程输入IO的个数
+ ("pPresetLutDesc", POINTER(tSdkPresetLut)), #相机预设的LUT表
+ ("iPresetLut", c_int), #相机预设的LUT表的个数,即pPresetLutDesc数组的大小
+ ("iUserDataMaxLen", c_int), #指示该相机中用于保存用户数据区的最大长度。为0表示无。
+ ("bParamInDevice", c_int), #指示该设备是否支持从设备中读写参数组。1为支持,0不支持。
+ ("pAeAlmSwDesc", POINTER(tSdkAeAlgorithm)),#软件自动曝光算法描述
+ ("iAeAlmSwDesc", c_int), #软件自动曝光算法个数
+ ("pAeAlmHdDesc", POINTER(tSdkAeAlgorithm)),#硬件自动曝光算法描述,为NULL表示不支持硬件自动曝光
+ ("iAeAlmHdDesc", c_int), #硬件自动曝光算法个数,为0表示不支持硬件自动曝光
+ ("pBayerDecAlmSwDesc", POINTER(tSdkBayerDecodeAlgorithm)),#软件Bayer转换为RGB数据的算法描述
+ ("iBayerDecAlmSwDesc", c_int), #软件Bayer转换为RGB数据的算法个数
+ ("pBayerDecAlmHdDesc", POINTER(tSdkBayerDecodeAlgorithm)),#硬件Bayer转换为RGB数据的算法描述,为NULL表示不支持
+ ("iBayerDecAlmHdDesc", c_int), #硬件Bayer转换为RGB数据的算法个数,为0表示不支持
+
+ # 图像参数的调节范围定义,用于动态构建UI
+ ("sExposeDesc", tSdkExpose), #曝光的范围值
+ ("sResolutionRange", tSdkResolutionRange), #分辨率范围描述
+ ("sRgbGainRange", tRgbGainRange), #图像数字增益范围描述
+ ("sSaturationRange", tSaturationRange), #饱和度范围描述
+ ("sGammaRange", tGammaRange), #伽马范围描述
+ ("sContrastRange", tContrastRange), #对比度范围描述
+ ("sSharpnessRange", tSharpnessRange), #锐化范围描述
+ ("sIspCapacity", tSdkIspCapacity), #ISP能力描述
+ ]
+
+#图像帧头信息
+class tSdkFrameHead(MvStructure):
+ _fields_ = [
+ ("uiMediaType", c_uint), # 图像格式,Image Format
+ ("uBytes", c_uint), # 图像数据字节数,Total bytes
+ ("iWidth", c_int), # 宽度 Image height
+ ("iHeight", c_int), # 高度 Image width
+ ("iWidthZoomSw", c_int), # 软件缩放的宽度,不需要进行软件裁剪的图像,此变量设置为0.
+ ("iHeightZoomSw", c_int), # 软件缩放的高度,不需要进行软件裁剪的图像,此变量设置为0.
+ ("bIsTrigger", c_int), # 指示是否为触发帧 is trigger
+ ("uiTimeStamp", c_uint), # 该帧的采集时间,单位0.1毫秒
+ ("uiExpTime", c_uint), # 当前图像的曝光值,单位为微秒us
+ ("fAnalogGain", c_float), # 当前图像的模拟增益倍数
+ ("iGamma", c_int), # 该帧图像的伽马设定值,仅当LUT模式为动态参数生成时有效,其余模式下为-1
+ ("iContrast", c_int), # 该帧图像的对比度设定值,仅当LUT模式为动态参数生成时有效,其余模式下为-1
+ ("iSaturation", c_int), # 该帧图像的饱和度设定值,对于黑白相机无意义,为0
+ ("fRgain", c_float), # 该帧图像处理的红色数字增益倍数,对于黑白相机无意义,为1
+ ("fGgain", c_float), # 该帧图像处理的绿色数字增益倍数,对于黑白相机无意义,为1
+ ("fBgain", c_float), # 该帧图像处理的蓝色数字增益倍数,对于黑白相机无意义,为1
+ ]
+
+# Grabber统计信息
+class tSdkGrabberStat(MvStructure):
+ _fields_ = [
+ ("Width", c_int), # 帧图像大小
+ ("Height", c_int), # 帧图像大小
+ ("Disp", c_int), # 显示帧数量
+ ("Capture", c_int), # 采集的有效帧的数量
+ ("Lost", c_int), # 丢帧的数量
+ ("Error", c_int), # 错帧的数量
+ ("DispFps", c_float), # 显示帧率
+ ("CapFps", c_float), # 捕获帧率
+ ]
+
+# 方法回调辅助类
+class method(object):
+ def __init__(self, FuncType):
+ super(method, self).__init__()
+ self.FuncType = FuncType
+ self.cache = {}
+
+ def __call__(self, cb):
+ self.cb = cb
+ return self
+
+ def __get__(self, obj, objtype):
+ try:
+ return self.cache[obj]
+ except KeyError as e:
+ def cl(*args):
+ return self.cb(obj, *args)
+ r = self.cache[obj] = self.FuncType(cl)
+ return r
+
+# 图像捕获的回调函数定义
+CAMERA_SNAP_PROC = CALLBACK_FUNC_TYPE(None, c_int, c_void_p, POINTER(tSdkFrameHead), c_void_p)
+
+# 相机连接状态回调
+CAMERA_CONNECTION_STATUS_CALLBACK = CALLBACK_FUNC_TYPE(None, c_int, c_uint, c_uint, c_void_p)
+
+# 异步抓图完成回调
+pfnCameraGrabberSaveImageComplete = CALLBACK_FUNC_TYPE(None, c_void_p, c_void_p, c_int, c_void_p)
+
+# 帧监听回调
+pfnCameraGrabberFrameListener = CALLBACK_FUNC_TYPE(c_int, c_void_p, c_int, c_void_p, POINTER(tSdkFrameHead), c_void_p)
+
+# 采集器图像捕获的回调
+pfnCameraGrabberFrameCallback = CALLBACK_FUNC_TYPE(None, c_void_p, c_void_p, POINTER(tSdkFrameHead), c_void_p)
+
+#-----------------------------------函数接口------------------------------------------
+
+# 线程局部存储
+_tls = local()
+
+# 存储最后一次SDK调用返回的错误码
+def GetLastError():
+ try:
+ return _tls.last_error
+ except AttributeError as e:
+ _tls.last_error = 0
+ return 0
+
+def SetLastError(err_code):
+ _tls.last_error = err_code
+
+def _string_buffer_to_str(buf):
+ s = buf if isinstance(buf, type(b'')) else buf.value
+
+ for codec in ('gbk', 'utf-8'):
+ try:
+ s = s.decode(codec)
+ break
+ except UnicodeDecodeError as e:
+ continue
+
+ if isinstance(s, str):
+ return s
+ else:
+ return s.encode('utf-8')
+
+def _str_to_string_buffer(str):
+ if type(str) is type(u''):
+ s = str.encode('gbk')
+ else:
+ s = str.decode('utf-8').encode('gbk')
+ return create_string_buffer(s)
+
+def CameraSdkInit(iLanguageSel):
+ err_code = _sdk.CameraSdkInit(iLanguageSel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraEnumerateDevice(MaxCount = 32):
+ Nums = c_int(MaxCount)
+ pCameraList = (tSdkCameraDevInfo * Nums.value)()
+ err_code = _sdk.CameraEnumerateDevice(pCameraList, byref(Nums))
+ SetLastError(err_code)
+ return pCameraList[0:Nums.value]
+
+def CameraEnumerateDeviceEx():
+ return _sdk.CameraEnumerateDeviceEx()
+
+def CameraIsOpened(pCameraInfo):
+ pOpened = c_int()
+ err_code = _sdk.CameraIsOpened(byref(pCameraInfo), byref(pOpened) )
+ SetLastError(err_code)
+ return pOpened.value != 0
+
+def CameraInit(pCameraInfo, emParamLoadMode = -1, emTeam = -1):
+ pCameraHandle = c_int()
+ err_code = _sdk.CameraInit(byref(pCameraInfo), emParamLoadMode, emTeam, byref(pCameraHandle))
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return pCameraHandle.value
+
+def CameraInitEx(iDeviceIndex, emParamLoadMode = -1, emTeam = -1):
+ pCameraHandle = c_int()
+ err_code = _sdk.CameraInitEx(iDeviceIndex, emParamLoadMode, emTeam, byref(pCameraHandle))
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return pCameraHandle.value
+
+def CameraInitEx2(CameraName):
+ pCameraHandle = c_int()
+ err_code = _sdk.CameraInitEx2(_str_to_string_buffer(CameraName), byref(pCameraHandle))
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return pCameraHandle.value
+
+def CameraSetCallbackFunction(hCamera, pCallBack, pContext = 0):
+ err_code = _sdk.CameraSetCallbackFunction(hCamera, pCallBack, c_void_p(pContext), None)
+ SetLastError(err_code)
+ return err_code
+
+def CameraUnInit(hCamera):
+ err_code = _sdk.CameraUnInit(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetInformation(hCamera):
+ pbuffer = c_char_p()
+ err_code = _sdk.CameraGetInformation(hCamera, byref(pbuffer) )
+ SetLastError(err_code)
+ if err_code == 0 and pbuffer.value is not None:
+ return _string_buffer_to_str(pbuffer)
+ return ''
+
+def CameraImageProcess(hCamera, pbyIn, pbyOut, pFrInfo):
+ err_code = _sdk.CameraImageProcess(hCamera, c_void_p(pbyIn), c_void_p(pbyOut), byref(pFrInfo))
+ SetLastError(err_code)
+ return err_code
+
+def CameraImageProcessEx(hCamera, pbyIn, pbyOut, pFrInfo, uOutFormat, uReserved):
+ err_code = _sdk.CameraImageProcessEx(hCamera, c_void_p(pbyIn), c_void_p(pbyOut), byref(pFrInfo), uOutFormat, uReserved)
+ SetLastError(err_code)
+ return err_code
+
+def CameraDisplayInit(hCamera, hWndDisplay):
+ err_code = _sdk.CameraDisplayInit(hCamera, hWndDisplay)
+ SetLastError(err_code)
+ return err_code
+
+def CameraDisplayRGB24(hCamera, pFrameBuffer, pFrInfo):
+ err_code = _sdk.CameraDisplayRGB24(hCamera, c_void_p(pFrameBuffer), byref(pFrInfo) )
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetDisplayMode(hCamera, iMode):
+ err_code = _sdk.CameraSetDisplayMode(hCamera, iMode)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetDisplayOffset(hCamera, iOffsetX, iOffsetY):
+ err_code = _sdk.CameraSetDisplayOffset(hCamera, iOffsetX, iOffsetY)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetDisplaySize(hCamera, iWidth, iHeight):
+ err_code = _sdk.CameraSetDisplaySize(hCamera, iWidth, iHeight)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetImageBuffer(hCamera, wTimes):
+ pbyBuffer = c_void_p()
+ pFrameInfo = tSdkFrameHead()
+ err_code = _sdk.CameraGetImageBuffer(hCamera, byref(pFrameInfo), byref(pbyBuffer), wTimes)
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return (pbyBuffer.value, pFrameInfo)
+
+def CameraGetImageBufferEx(hCamera, wTimes):
+ _sdk.CameraGetImageBufferEx.restype = c_void_p
+ piWidth = c_int()
+ piHeight = c_int()
+ pFrameBuffer = _sdk.CameraGetImageBufferEx(hCamera, byref(piWidth), byref(piHeight), wTimes)
+ err_code = CAMERA_STATUS_SUCCESS if pFrameBuffer else CAMERA_STATUS_TIME_OUT
+ SetLastError(err_code)
+ if pFrameBuffer:
+ return (pFrameBuffer, piWidth.value, piHeight.value)
+ else:
+ raise CameraException(err_code)
+
+def CameraSnapToBuffer(hCamera, wTimes):
+ pbyBuffer = c_void_p()
+ pFrameInfo = tSdkFrameHead()
+ err_code = _sdk.CameraSnapToBuffer(hCamera, byref(pFrameInfo), byref(pbyBuffer), wTimes)
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return (pbyBuffer.value, pFrameInfo)
+
+def CameraReleaseImageBuffer(hCamera, pbyBuffer):
+ err_code = _sdk.CameraReleaseImageBuffer(hCamera, c_void_p(pbyBuffer) )
+ SetLastError(err_code)
+ return err_code
+
+def CameraPlay(hCamera):
+ err_code = _sdk.CameraPlay(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraPause(hCamera):
+ err_code = _sdk.CameraPause(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraStop(hCamera):
+ err_code = _sdk.CameraStop(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraInitRecord(hCamera, iFormat, pcSavePath, b2GLimit, dwQuality, iFrameRate):
+ err_code = _sdk.CameraInitRecord(hCamera, iFormat, _str_to_string_buffer(pcSavePath), b2GLimit, dwQuality, iFrameRate)
+ SetLastError(err_code)
+ return err_code
+
+def CameraStopRecord(hCamera):
+ err_code = _sdk.CameraStopRecord(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraPushFrame(hCamera, pbyImageBuffer, pFrInfo):
+ err_code = _sdk.CameraPushFrame(hCamera, c_void_p(pbyImageBuffer), byref(pFrInfo) )
+ SetLastError(err_code)
+ return err_code
+
+def CameraSaveImage(hCamera, lpszFileName, pbyImageBuffer, pFrInfo, byFileType, byQuality):
+ err_code = _sdk.CameraSaveImage(hCamera, _str_to_string_buffer(lpszFileName), c_void_p(pbyImageBuffer), byref(pFrInfo), byFileType, byQuality)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSaveImageEx(hCamera, lpszFileName, pbyImageBuffer, uImageFormat, iWidth, iHeight, byFileType, byQuality):
+ err_code = _sdk.CameraSaveImageEx(hCamera, _str_to_string_buffer(lpszFileName), c_void_p(pbyImageBuffer), uImageFormat, iWidth, iHeight, byFileType, byQuality)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetImageResolution(hCamera):
+ psCurVideoSize = tSdkImageResolution()
+ err_code = _sdk.CameraGetImageResolution(hCamera, byref(psCurVideoSize) )
+ SetLastError(err_code)
+ return psCurVideoSize
+
+def CameraSetImageResolution(hCamera, pImageResolution):
+ err_code = _sdk.CameraSetImageResolution(hCamera, byref(pImageResolution) )
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetImageResolutionEx(hCamera, iIndex, Mode, ModeSize, x, y, width, height, ZoomWidth, ZoomHeight):
+ err_code = _sdk.CameraSetImageResolutionEx(hCamera, iIndex, Mode, ModeSize, x, y, width, height, ZoomWidth, ZoomHeight)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetMediaType(hCamera):
+ piMediaType = c_int()
+ err_code = _sdk.CameraGetMediaType(hCamera, byref(piMediaType) )
+ SetLastError(err_code)
+ return piMediaType.value
+
+def CameraSetMediaType(hCamera, iMediaType):
+ err_code = _sdk.CameraSetMediaType(hCamera, iMediaType)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetAeState(hCamera, bAeState):
+ err_code = _sdk.CameraSetAeState(hCamera, bAeState)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetAeState(hCamera):
+ pAeState = c_int()
+ err_code = _sdk.CameraGetAeState(hCamera, byref(pAeState) )
+ SetLastError(err_code)
+ return pAeState.value
+
+def CameraSetSharpness(hCamera, iSharpness):
+ err_code = _sdk.CameraSetSharpness(hCamera, iSharpness)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetSharpness(hCamera):
+ piSharpness = c_int()
+ err_code = _sdk.CameraGetSharpness(hCamera, byref(piSharpness) )
+ SetLastError(err_code)
+ return piSharpness.value
+
+def CameraSetLutMode(hCamera, emLutMode):
+ err_code = _sdk.CameraSetLutMode(hCamera, emLutMode)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetLutMode(hCamera):
+ pemLutMode = c_int()
+ err_code = _sdk.CameraGetLutMode(hCamera, byref(pemLutMode) )
+ SetLastError(err_code)
+ return pemLutMode.value
+
+def CameraSelectLutPreset(hCamera, iSel):
+ err_code = _sdk.CameraSelectLutPreset(hCamera, iSel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetLutPresetSel(hCamera):
+ piSel = c_int()
+ err_code = _sdk.CameraGetLutPresetSel(hCamera, byref(piSel) )
+ SetLastError(err_code)
+ return piSel.value
+
+def CameraSetCustomLut(hCamera, iChannel, pLut):
+ pLutNative = (c_ushort * 4096)(*pLut)
+ err_code = _sdk.CameraSetCustomLut(hCamera, iChannel, pLutNative)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetCustomLut(hCamera, iChannel):
+ pLutNative = (c_ushort * 4096)()
+ err_code = _sdk.CameraGetCustomLut(hCamera, iChannel, pLutNative)
+ SetLastError(err_code)
+ return pLutNative[:]
+
+def CameraGetCurrentLut(hCamera, iChannel):
+ pLutNative = (c_ushort * 4096)()
+ err_code = _sdk.CameraGetCurrentLut(hCamera, iChannel, pLutNative)
+ SetLastError(err_code)
+ return pLutNative[:]
+
+def CameraSetWbMode(hCamera, bAuto):
+ err_code = _sdk.CameraSetWbMode(hCamera, bAuto)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetWbMode(hCamera):
+ pbAuto = c_int()
+ err_code = _sdk.CameraGetWbMode(hCamera, byref(pbAuto) )
+ SetLastError(err_code)
+ return pbAuto.value
+
+def CameraSetPresetClrTemp(hCamera, iSel):
+ err_code = _sdk.CameraSetPresetClrTemp(hCamera, iSel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetPresetClrTemp(hCamera):
+ piSel = c_int()
+ err_code = _sdk.CameraGetPresetClrTemp(hCamera, byref(piSel) )
+ SetLastError(err_code)
+ return piSel.value
+
+def CameraSetUserClrTempGain(hCamera, iRgain, iGgain, iBgain):
+ err_code = _sdk.CameraSetUserClrTempGain(hCamera, iRgain, iGgain, iBgain)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetUserClrTempGain(hCamera):
+ piRgain = c_int()
+ piGgain = c_int()
+ piBgain = c_int()
+ err_code = _sdk.CameraGetUserClrTempGain(hCamera, byref(piRgain), byref(piGgain), byref(piBgain) )
+ SetLastError(err_code)
+ return (piRgain.value, piGgain.value, piBgain.value)
+
+def CameraSetUserClrTempMatrix(hCamera, pMatrix):
+ pMatrixNative = (c_float * 9)(*pMatrix)
+ err_code = _sdk.CameraSetUserClrTempMatrix(hCamera, pMatrixNative)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetUserClrTempMatrix(hCamera):
+ pMatrixNative = (c_float * 9)()
+ err_code = _sdk.CameraGetUserClrTempMatrix(hCamera, pMatrixNative)
+ SetLastError(err_code)
+ return pMatrixNative[:]
+
+def CameraSetClrTempMode(hCamera, iMode):
+ err_code = _sdk.CameraSetClrTempMode(hCamera, iMode)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetClrTempMode(hCamera):
+ piMode = c_int()
+ err_code = _sdk.CameraGetClrTempMode(hCamera, byref(piMode) )
+ SetLastError(err_code)
+ return piMode.value
+
+def CameraSetOnceWB(hCamera):
+ err_code = _sdk.CameraSetOnceWB(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetOnceBB(hCamera):
+ err_code = _sdk.CameraSetOnceBB(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetAeTarget(hCamera, iAeTarget):
+ err_code = _sdk.CameraSetAeTarget(hCamera, iAeTarget)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetAeTarget(hCamera):
+ piAeTarget = c_int()
+ err_code = _sdk.CameraGetAeTarget(hCamera, byref(piAeTarget) )
+ SetLastError(err_code)
+ return piAeTarget.value
+
+def CameraSetAeExposureRange(hCamera, fMinExposureTime, fMaxExposureTime):
+ err_code = _sdk.CameraSetAeExposureRange(hCamera, c_double(fMinExposureTime), c_double(fMaxExposureTime) )
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetAeExposureRange(hCamera):
+ fMinExposureTime = c_double()
+ fMaxExposureTime = c_double()
+ err_code = _sdk.CameraGetAeExposureRange(hCamera, byref(fMinExposureTime), byref(fMaxExposureTime) )
+ SetLastError(err_code)
+ return (fMinExposureTime.value, fMaxExposureTime.value)
+
+def CameraSetAeAnalogGainRange(hCamera, iMinAnalogGain, iMaxAnalogGain):
+ err_code = _sdk.CameraSetAeAnalogGainRange(hCamera, iMinAnalogGain, iMaxAnalogGain)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetAeAnalogGainRange(hCamera):
+ iMinAnalogGain = c_int()
+ iMaxAnalogGain = c_int()
+ err_code = _sdk.CameraGetAeAnalogGainRange(hCamera, byref(iMinAnalogGain), byref(iMaxAnalogGain) )
+ SetLastError(err_code)
+ return (iMinAnalogGain.value, iMaxAnalogGain.value)
+
+def CameraSetAeThreshold(hCamera, iThreshold):
+ err_code = _sdk.CameraSetAeThreshold(hCamera, iThreshold)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetAeThreshold(hCamera):
+ iThreshold = c_int()
+ err_code = _sdk.CameraGetAeThreshold(hCamera, byref(iThreshold))
+ SetLastError(err_code)
+ return iThreshold.value
+
+def CameraSetExposureTime(hCamera, fExposureTime):
+ err_code = _sdk.CameraSetExposureTime(hCamera, c_double(fExposureTime) )
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetExposureLineTime(hCamera):
+ pfLineTime = c_double()
+ err_code = _sdk.CameraGetExposureLineTime(hCamera, byref(pfLineTime))
+ SetLastError(err_code)
+ return pfLineTime.value
+
+def CameraGetExposureTime(hCamera):
+ pfExposureTime = c_double()
+ err_code = _sdk.CameraGetExposureTime(hCamera, byref(pfExposureTime))
+ SetLastError(err_code)
+ return pfExposureTime.value
+
+def CameraGetExposureTimeRange(hCamera):
+ pfMin = c_double()
+ pfMax = c_double()
+ pfStep = c_double()
+ err_code = _sdk.CameraGetExposureTimeRange(hCamera, byref(pfMin), byref(pfMax), byref(pfStep))
+ SetLastError(err_code)
+ return (pfMin.value, pfMax.value, pfStep.value)
+
+def CameraSetAnalogGain(hCamera, iAnalogGain):
+ err_code = _sdk.CameraSetAnalogGain(hCamera, iAnalogGain)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetAnalogGain(hCamera):
+ piAnalogGain = c_int()
+ err_code = _sdk.CameraGetAnalogGain(hCamera, byref(piAnalogGain))
+ SetLastError(err_code)
+ return piAnalogGain.value
+
+def CameraSetGain(hCamera, iRGain, iGGain, iBGain):
+ err_code = _sdk.CameraSetGain(hCamera, iRGain, iGGain, iBGain)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetGain(hCamera):
+ piRGain = c_int()
+ piGGain = c_int()
+ piBGain = c_int()
+ err_code = _sdk.CameraGetGain(hCamera, byref(piRGain), byref(piGGain), byref(piBGain))
+ SetLastError(err_code)
+ return (piRGain.value, piGGain.value, piBGain.value)
+
+def CameraSetGamma(hCamera, iGamma):
+ err_code = _sdk.CameraSetGamma(hCamera, iGamma)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetGamma(hCamera):
+ piGamma = c_int()
+ err_code = _sdk.CameraGetGamma(hCamera, byref(piGamma))
+ SetLastError(err_code)
+ return piGamma.value
+
+def CameraSetContrast(hCamera, iContrast):
+ err_code = _sdk.CameraSetContrast(hCamera, iContrast)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetContrast(hCamera):
+ piContrast = c_int()
+ err_code = _sdk.CameraGetContrast(hCamera, byref(piContrast))
+ SetLastError(err_code)
+ return piContrast.value
+
+def CameraSetSaturation(hCamera, iSaturation):
+ err_code = _sdk.CameraSetSaturation(hCamera, iSaturation)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetSaturation(hCamera):
+ piSaturation = c_int()
+ err_code = _sdk.CameraGetSaturation(hCamera, byref(piSaturation))
+ SetLastError(err_code)
+ return piSaturation.value
+
+def CameraSetMonochrome(hCamera, bEnable):
+ err_code = _sdk.CameraSetMonochrome(hCamera, bEnable)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetMonochrome(hCamera):
+ pbEnable = c_int()
+ err_code = _sdk.CameraGetMonochrome(hCamera, byref(pbEnable))
+ SetLastError(err_code)
+ return pbEnable.value
+
+def CameraSetInverse(hCamera, bEnable):
+ err_code = _sdk.CameraSetInverse(hCamera, bEnable)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetInverse(hCamera):
+ pbEnable = c_int()
+ err_code = _sdk.CameraGetInverse(hCamera, byref(pbEnable))
+ SetLastError(err_code)
+ return pbEnable.value
+
+def CameraSetAntiFlick(hCamera, bEnable):
+ err_code = _sdk.CameraSetAntiFlick(hCamera, bEnable)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetAntiFlick(hCamera):
+ pbEnable = c_int()
+ err_code = _sdk.CameraGetAntiFlick(hCamera, byref(pbEnable))
+ SetLastError(err_code)
+ return pbEnable.value
+
+def CameraGetLightFrequency(hCamera):
+ piFrequencySel = c_int()
+ err_code = _sdk.CameraGetLightFrequency(hCamera, byref(piFrequencySel))
+ SetLastError(err_code)
+ return piFrequencySel.value
+
+def CameraSetLightFrequency(hCamera, iFrequencySel):
+ err_code = _sdk.CameraSetLightFrequency(hCamera, iFrequencySel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetFrameSpeed(hCamera, iFrameSpeed):
+ err_code = _sdk.CameraSetFrameSpeed(hCamera, iFrameSpeed)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetFrameSpeed(hCamera):
+ piFrameSpeed = c_int()
+ err_code = _sdk.CameraGetFrameSpeed(hCamera, byref(piFrameSpeed))
+ SetLastError(err_code)
+ return piFrameSpeed.value
+
+def CameraSetParameterMode(hCamera, iMode):
+ err_code = _sdk.CameraSetParameterMode(hCamera, iMode)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetParameterMode(hCamera):
+ piTarget = c_int()
+ err_code = _sdk.CameraGetParameterMode(hCamera, byref(piTarget))
+ SetLastError(err_code)
+ return piTarget.value
+
+def CameraSetParameterMask(hCamera, uMask):
+ err_code = _sdk.CameraSetParameterMask(hCamera, uMask)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSaveParameter(hCamera, iTeam):
+ err_code = _sdk.CameraSaveParameter(hCamera, iTeam)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSaveParameterToFile(hCamera, sFileName):
+ err_code = _sdk.CameraSaveParameterToFile(hCamera, _str_to_string_buffer(sFileName))
+ SetLastError(err_code)
+ return err_code
+
+def CameraReadParameterFromFile(hCamera, sFileName):
+ err_code = _sdk.CameraReadParameterFromFile(hCamera, _str_to_string_buffer(sFileName))
+ SetLastError(err_code)
+ return err_code
+
+def CameraLoadParameter(hCamera, iTeam):
+ err_code = _sdk.CameraLoadParameter(hCamera, iTeam)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetCurrentParameterGroup(hCamera):
+ piTeam = c_int()
+ err_code = _sdk.CameraGetCurrentParameterGroup(hCamera, byref(piTeam))
+ SetLastError(err_code)
+ return piTeam.value
+
+def CameraSetTransPackLen(hCamera, iPackSel):
+ err_code = _sdk.CameraSetTransPackLen(hCamera, iPackSel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetTransPackLen(hCamera):
+ piPackSel = c_int()
+ err_code = _sdk.CameraGetTransPackLen(hCamera, byref(piPackSel))
+ SetLastError(err_code)
+ return piPackSel.value
+
+def CameraIsAeWinVisible(hCamera):
+ pbIsVisible = c_int()
+ err_code = _sdk.CameraIsAeWinVisible(hCamera, byref(pbIsVisible))
+ SetLastError(err_code)
+ return pbIsVisible.value
+
+def CameraSetAeWinVisible(hCamera, bIsVisible):
+ err_code = _sdk.CameraSetAeWinVisible(hCamera, bIsVisible)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetAeWindow(hCamera):
+ piHOff = c_int()
+ piVOff = c_int()
+ piWidth = c_int()
+ piHeight = c_int()
+ err_code = _sdk.CameraGetAeWindow(hCamera, byref(piHOff), byref(piVOff), byref(piWidth), byref(piHeight))
+ SetLastError(err_code)
+ return (piHOff.value, piVOff.value, piWidth.value, piHeight.value)
+
+def CameraSetAeWindow(hCamera, iHOff, iVOff, iWidth, iHeight):
+ err_code = _sdk.CameraSetAeWindow(hCamera, iHOff, iVOff, iWidth, iHeight)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetMirror(hCamera, iDir, bEnable):
+ err_code = _sdk.CameraSetMirror(hCamera, iDir, bEnable)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetMirror(hCamera, iDir):
+ pbEnable = c_int()
+ err_code = _sdk.CameraGetMirror(hCamera, iDir, byref(pbEnable))
+ SetLastError(err_code)
+ return pbEnable.value
+
+def CameraSetRotate(hCamera, iRot):
+ err_code = _sdk.CameraSetRotate(hCamera, iRot)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetRotate(hCamera):
+ iRot = c_int()
+ err_code = _sdk.CameraGetRotate(hCamera, byref(iRot))
+ SetLastError(err_code)
+ return iRot.value
+
+def CameraGetWbWindow(hCamera):
+ PiHOff = c_int()
+ PiVOff = c_int()
+ PiWidth = c_int()
+ PiHeight = c_int()
+ err_code = _sdk.CameraGetWbWindow(hCamera, byref(PiHOff), byref(PiVOff), byref(PiWidth), byref(PiHeight))
+ SetLastError(err_code)
+ return (PiHOff.value, PiVOff.value, PiWidth.value, PiHeight.value)
+
+def CameraSetWbWindow(hCamera, iHOff, iVOff, iWidth, iHeight):
+ err_code = _sdk.CameraSetWbWindow(hCamera, iHOff, iVOff, iWidth, iHeight)
+ SetLastError(err_code)
+ return err_code
+
+def CameraIsWbWinVisible(hCamera):
+ pbShow = c_int()
+ err_code = _sdk.CameraIsWbWinVisible(hCamera, byref(pbShow))
+ SetLastError(err_code)
+ return pbShow.value
+
+def CameraSetWbWinVisible(hCamera, bShow):
+ err_code = _sdk.CameraSetWbWinVisible(hCamera, bShow)
+ SetLastError(err_code)
+ return err_code
+
+def CameraImageOverlay(hCamera, pRgbBuffer, pFrInfo):
+ err_code = _sdk.CameraImageOverlay(hCamera, c_void_p(pRgbBuffer), byref(pFrInfo))
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetCrossLine(hCamera, iLine, x, y, uColor, bVisible):
+ err_code = _sdk.CameraSetCrossLine(hCamera, iLine, x, y, uColor, bVisible)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetCrossLine(hCamera, iLine):
+ px = c_int()
+ py = c_int()
+ pcolor = c_uint()
+ pbVisible = c_int()
+ err_code = _sdk.CameraGetCrossLine(hCamera, iLine, byref(px), byref(py), byref(pcolor), byref(pbVisible))
+ SetLastError(err_code)
+ return (px.value, py.value, pcolor.value, pbVisible.value)
+
+def CameraGetCapability(hCamera):
+ pCameraInfo = tSdkCameraCapbility()
+ err_code = _sdk.CameraGetCapability(hCamera, byref(pCameraInfo))
+ SetLastError(err_code)
+ return pCameraInfo
+
+def CameraWriteSN(hCamera, pbySN, iLevel):
+ err_code = _sdk.CameraWriteSN(hCamera, _str_to_string_buffer(pbySN), iLevel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraReadSN(hCamera, iLevel):
+ pbySN = create_string_buffer(64)
+ err_code = _sdk.CameraReadSN(hCamera, pbySN, iLevel)
+ SetLastError(err_code)
+ return _string_buffer_to_str(pbySN)
+
+def CameraSetTriggerDelayTime(hCamera, uDelayTimeUs):
+ err_code = _sdk.CameraSetTriggerDelayTime(hCamera, uDelayTimeUs)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetTriggerDelayTime(hCamera):
+ puDelayTimeUs = c_uint()
+ err_code = _sdk.CameraGetTriggerDelayTime(hCamera, byref(puDelayTimeUs))
+ SetLastError(err_code)
+ return puDelayTimeUs.value
+
+def CameraSetTriggerCount(hCamera, iCount):
+ err_code = _sdk.CameraSetTriggerCount(hCamera, iCount)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetTriggerCount(hCamera):
+ piCount = c_int()
+ err_code = _sdk.CameraGetTriggerCount(hCamera, byref(piCount))
+ SetLastError(err_code)
+ return piCount.value
+
+def CameraSoftTrigger(hCamera):
+ err_code = _sdk.CameraSoftTrigger(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetTriggerMode(hCamera, iModeSel):
+ err_code = _sdk.CameraSetTriggerMode(hCamera, iModeSel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetTriggerMode(hCamera):
+ piModeSel = c_int()
+ err_code = _sdk.CameraGetTriggerMode(hCamera, byref(piModeSel))
+ SetLastError(err_code)
+ return piModeSel.value
+
+def CameraSetStrobeMode(hCamera, iMode):
+ err_code = _sdk.CameraSetStrobeMode(hCamera, iMode)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetStrobeMode(hCamera):
+ piMode = c_int()
+ err_code = _sdk.CameraGetStrobeMode(hCamera, byref(piMode))
+ SetLastError(err_code)
+ return piMode.value
+
+def CameraSetStrobeDelayTime(hCamera, uDelayTimeUs):
+ err_code = _sdk.CameraSetStrobeDelayTime(hCamera, uDelayTimeUs)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetStrobeDelayTime(hCamera):
+ upDelayTimeUs = c_uint()
+ err_code = _sdk.CameraGetStrobeDelayTime(hCamera, byref(upDelayTimeUs))
+ SetLastError(err_code)
+ return upDelayTimeUs.value
+
+def CameraSetStrobePulseWidth(hCamera, uTimeUs):
+ err_code = _sdk.CameraSetStrobePulseWidth(hCamera, uTimeUs)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetStrobePulseWidth(hCamera):
+ upTimeUs = c_uint()
+ err_code = _sdk.CameraGetStrobePulseWidth(hCamera, byref(upTimeUs))
+ SetLastError(err_code)
+ return upTimeUs.value
+
+def CameraSetStrobePolarity(hCamera, uPolarity):
+ err_code = _sdk.CameraSetStrobePolarity(hCamera, uPolarity)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetStrobePolarity(hCamera):
+ upPolarity = c_uint()
+ err_code = _sdk.CameraGetStrobePolarity(hCamera, byref(upPolarity))
+ SetLastError(err_code)
+ return upPolarity.value
+
+def CameraSetExtTrigSignalType(hCamera, iType):
+ err_code = _sdk.CameraSetExtTrigSignalType(hCamera, iType)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetExtTrigSignalType(hCamera):
+ ipType = c_int()
+ err_code = _sdk.CameraGetExtTrigSignalType(hCamera, byref(ipType))
+ SetLastError(err_code)
+ return ipType.value
+
+def CameraSetExtTrigShutterType(hCamera, iType):
+ err_code = _sdk.CameraSetExtTrigShutterType(hCamera, iType)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetExtTrigShutterType(hCamera):
+ ipType = c_int()
+ err_code = _sdk.CameraGetExtTrigShutterType(hCamera, byref(ipType))
+ SetLastError(err_code)
+ return ipType.value
+
+def CameraSetExtTrigDelayTime(hCamera, uDelayTimeUs):
+ err_code = _sdk.CameraSetExtTrigDelayTime(hCamera, uDelayTimeUs)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetExtTrigDelayTime(hCamera):
+ upDelayTimeUs = c_uint()
+ err_code = _sdk.CameraGetExtTrigDelayTime(hCamera, byref(upDelayTimeUs))
+ SetLastError(err_code)
+ return upDelayTimeUs.value
+
+def CameraSetExtTrigJitterTime(hCamera, uTimeUs):
+ err_code = _sdk.CameraSetExtTrigJitterTime(hCamera, uTimeUs)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetExtTrigJitterTime(hCamera):
+ upTimeUs = c_uint()
+ err_code = _sdk.CameraGetExtTrigJitterTime(hCamera, byref(upTimeUs))
+ SetLastError(err_code)
+ return upTimeUs.value
+
+def CameraGetExtTrigCapability(hCamera):
+ puCapabilityMask = c_uint()
+ err_code = _sdk.CameraGetExtTrigCapability(hCamera, byref(puCapabilityMask))
+ SetLastError(err_code)
+ return puCapabilityMask.value
+
+def CameraPauseLevelTrigger(hCamera):
+ err_code = _sdk.CameraPauseLevelTrigger(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetResolutionForSnap(hCamera):
+ pImageResolution = tSdkImageResolution()
+ err_code = _sdk.CameraGetResolutionForSnap(hCamera, byref(pImageResolution))
+ SetLastError(err_code)
+ return pImageResolution
+
+def CameraSetResolutionForSnap(hCamera, pImageResolution):
+ err_code = _sdk.CameraSetResolutionForSnap(hCamera, byref(pImageResolution))
+ SetLastError(err_code)
+ return err_code
+
+def CameraCustomizeResolution(hCamera):
+ pImageCustom = tSdkImageResolution()
+ err_code = _sdk.CameraCustomizeResolution(hCamera, byref(pImageCustom))
+ SetLastError(err_code)
+ return pImageCustom
+
+def CameraCustomizeReferWin(hCamera, iWinType, hParent):
+ piHOff = c_int()
+ piVOff = c_int()
+ piWidth = c_int()
+ piHeight = c_int()
+ err_code = _sdk.CameraCustomizeReferWin(hCamera, iWinType, hParent, byref(piHOff), byref(piVOff), byref(piWidth), byref(piHeight))
+ SetLastError(err_code)
+ return (piHOff.value, piVOff.value, piWidth.value, piHeight.value)
+
+def CameraShowSettingPage(hCamera, bShow):
+ err_code = _sdk.CameraShowSettingPage(hCamera, bShow)
+ SetLastError(err_code)
+ return err_code
+
+def CameraCreateSettingPage(hCamera, hParent, pWinText, pCallbackFunc = None, pCallbackCtx = 0, uReserved = 0):
+ err_code = _sdk.CameraCreateSettingPage(hCamera, hParent, _str_to_string_buffer(pWinText), pCallbackFunc, c_void_p(pCallbackCtx), uReserved)
+ SetLastError(err_code)
+ return err_code
+
+def CameraCreateSettingPageEx(hCamera):
+ err_code = _sdk.CameraCreateSettingPageEx(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetActiveSettingSubPage(hCamera, index):
+ err_code = _sdk.CameraSetActiveSettingSubPage(hCamera, index)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetSettingPageParent(hCamera, hParentWnd, Flags):
+ err_code = _sdk.CameraSetSettingPageParent(hCamera, hParentWnd, Flags)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetSettingPageHWnd(hCamera):
+ hWnd = c_void_p()
+ err_code = _sdk.CameraGetSettingPageHWnd(hCamera, byref(hWnd))
+ SetLastError(err_code)
+ return hWnd.value
+
+def CameraSpecialControl(hCamera, dwCtrlCode, dwParam, lpData):
+ err_code = _sdk.CameraSpecialControl(hCamera, dwCtrlCode, dwParam, c_void_p(lpData) )
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetFrameStatistic(hCamera):
+ psFrameStatistic = tSdkFrameStatistic()
+ err_code = _sdk.CameraGetFrameStatistic(hCamera, byref(psFrameStatistic))
+ SetLastError(err_code)
+ return psFrameStatistic
+
+def CameraSetNoiseFilter(hCamera, bEnable):
+ err_code = _sdk.CameraSetNoiseFilter(hCamera, bEnable)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetNoiseFilterState(hCamera):
+ pEnable = c_int()
+ err_code = _sdk.CameraGetNoiseFilterState(hCamera, byref(pEnable))
+ SetLastError(err_code)
+ return pEnable.value
+
+def CameraRstTimeStamp(hCamera):
+ err_code = _sdk.CameraRstTimeStamp(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSaveUserData(hCamera, uStartAddr, pbData):
+ err_code = _sdk.CameraSaveUserData(hCamera, uStartAddr, pbData, len(pbData))
+ SetLastError(err_code)
+ return err_code
+
+def CameraLoadUserData(hCamera, uStartAddr, ilen):
+ pbData = create_string_buffer(ilen)
+ err_code = _sdk.CameraLoadUserData(hCamera, uStartAddr, pbData, ilen)
+ SetLastError(err_code)
+ return pbData[:]
+
+def CameraGetFriendlyName(hCamera):
+ pName = create_string_buffer(64)
+ err_code = _sdk.CameraGetFriendlyName(hCamera, pName)
+ SetLastError(err_code)
+ return _string_buffer_to_str(pName)
+
+def CameraSetFriendlyName(hCamera, pName):
+ pNameBuf = _str_to_string_buffer(pName)
+ resize(pNameBuf, 64)
+ err_code = _sdk.CameraSetFriendlyName(hCamera, pNameBuf)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSdkGetVersionString():
+ pVersionString = create_string_buffer(64)
+ err_code = _sdk.CameraSdkGetVersionString(pVersionString)
+ SetLastError(err_code)
+ return _string_buffer_to_str(pVersionString)
+
+def CameraCheckFwUpdate(hCamera):
+ pNeedUpdate = c_int()
+ err_code = _sdk.CameraCheckFwUpdate(hCamera, byref(pNeedUpdate))
+ SetLastError(err_code)
+ return pNeedUpdate.value
+
+def CameraGetFirmwareVersion(hCamera):
+ pVersion = create_string_buffer(64)
+ err_code = _sdk.CameraGetFirmwareVersion(hCamera, pVersion)
+ SetLastError(err_code)
+ return _string_buffer_to_str(pVersion)
+
+def CameraGetEnumInfo(hCamera):
+ pCameraInfo = tSdkCameraDevInfo()
+ err_code = _sdk.CameraGetEnumInfo(hCamera, byref(pCameraInfo))
+ SetLastError(err_code)
+ return pCameraInfo
+
+def CameraGetInerfaceVersion(hCamera):
+ pVersion = create_string_buffer(64)
+ err_code = _sdk.CameraGetInerfaceVersion(hCamera, pVersion)
+ SetLastError(err_code)
+ return _string_buffer_to_str(pVersion)
+
+def CameraSetIOState(hCamera, iOutputIOIndex, uState):
+ err_code = _sdk.CameraSetIOState(hCamera, iOutputIOIndex, uState)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetIOState(hCamera, iInputIOIndex):
+ puState = c_int()
+ err_code = _sdk.CameraGetIOState(hCamera, iInputIOIndex, byref(puState))
+ SetLastError(err_code)
+ return puState.value
+
+def CameraSetInPutIOMode(hCamera, iInputIOIndex, iMode):
+ err_code = _sdk.CameraSetInPutIOMode(hCamera, iInputIOIndex, iMode)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetOutPutIOMode(hCamera, iOutputIOIndex, iMode):
+ err_code = _sdk.CameraSetOutPutIOMode(hCamera, iOutputIOIndex, iMode)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetOutPutPWM(hCamera, iOutputIOIndex, iCycle, uDuty):
+ err_code = _sdk.CameraSetOutPutPWM(hCamera, iOutputIOIndex, iCycle, uDuty)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetAeAlgorithm(hCamera, iIspProcessor, iAeAlgorithmSel):
+ err_code = _sdk.CameraSetAeAlgorithm(hCamera, iIspProcessor, iAeAlgorithmSel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetAeAlgorithm(hCamera, iIspProcessor):
+ piAlgorithmSel = c_int()
+ err_code = _sdk.CameraGetAeAlgorithm(hCamera, iIspProcessor, byref(piAlgorithmSel))
+ SetLastError(err_code)
+ return piAlgorithmSel.value
+
+def CameraSetBayerDecAlgorithm(hCamera, iIspProcessor, iAlgorithmSel):
+ err_code = _sdk.CameraSetBayerDecAlgorithm(hCamera, iIspProcessor, iAlgorithmSel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetBayerDecAlgorithm(hCamera, iIspProcessor):
+ piAlgorithmSel = c_int()
+ err_code = _sdk.CameraGetBayerDecAlgorithm(hCamera, iIspProcessor, byref(piAlgorithmSel))
+ SetLastError(err_code)
+ return piAlgorithmSel.value
+
+def CameraSetIspProcessor(hCamera, iIspProcessor):
+ err_code = _sdk.CameraSetIspProcessor(hCamera, iIspProcessor)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetIspProcessor(hCamera):
+ piIspProcessor = c_int()
+ err_code = _sdk.CameraGetIspProcessor(hCamera, byref(piIspProcessor))
+ SetLastError(err_code)
+ return piIspProcessor.value
+
+def CameraSetBlackLevel(hCamera, iBlackLevel):
+ err_code = _sdk.CameraSetBlackLevel(hCamera, iBlackLevel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetBlackLevel(hCamera):
+ piBlackLevel = c_int()
+ err_code = _sdk.CameraGetBlackLevel(hCamera, byref(piBlackLevel))
+ SetLastError(err_code)
+ return piBlackLevel.value
+
+def CameraSetWhiteLevel(hCamera, iWhiteLevel):
+ err_code = _sdk.CameraSetWhiteLevel(hCamera, iWhiteLevel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetWhiteLevel(hCamera):
+ piWhiteLevel = c_int()
+ err_code = _sdk.CameraGetWhiteLevel(hCamera, byref(piWhiteLevel))
+ SetLastError(err_code)
+ return piWhiteLevel.value
+
+def CameraSetIspOutFormat(hCamera, uFormat):
+ err_code = _sdk.CameraSetIspOutFormat(hCamera, uFormat)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetIspOutFormat(hCamera):
+ puFormat = c_int()
+ err_code = _sdk.CameraGetIspOutFormat(hCamera, byref(puFormat))
+ SetLastError(err_code)
+ return puFormat.value
+
+def CameraGetErrorString(iStatusCode):
+ _sdk.CameraGetErrorString.restype = c_char_p
+ msg = _sdk.CameraGetErrorString(iStatusCode)
+ if msg:
+ return _string_buffer_to_str(msg)
+ else:
+ return ''
+
+def CameraGetImageBufferEx2(hCamera, pImageData, uOutFormat, wTimes):
+ piWidth = c_int()
+ piHeight = c_int()
+ err_code = _sdk.CameraGetImageBufferEx2(hCamera, c_void_p(pImageData), uOutFormat, byref(piWidth), byref(piHeight), wTimes)
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return (piWidth.value, piHeight.value)
+
+def CameraGetImageBufferEx3(hCamera, pImageData, uOutFormat, wTimes):
+ piWidth = c_int()
+ piHeight = c_int()
+ puTimeStamp = c_int()
+ err_code = _sdk.CameraGetImageBufferEx3(hCamera, c_void_p(pImageData), uOutFormat, byref(piWidth), byref(piHeight), byref(puTimeStamp), wTimes)
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return (piWidth.value, piHeight.value, puTimeStamp.value)
+
+def CameraGetCapabilityEx2(hCamera):
+ pMaxWidth = c_int()
+ pMaxHeight = c_int()
+ pbColorCamera = c_int()
+ err_code = _sdk.CameraGetCapabilityEx2(hCamera, byref(pMaxWidth), byref(pMaxHeight), byref(pbColorCamera))
+ SetLastError(err_code)
+ return (pMaxWidth.value, pMaxHeight.value, pbColorCamera.value)
+
+def CameraReConnect(hCamera):
+ err_code = _sdk.CameraReConnect(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraConnectTest(hCamera):
+ err_code = _sdk.CameraConnectTest(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetLedEnable(hCamera, index, enable):
+ err_code = _sdk.CameraSetLedEnable(hCamera, index, enable)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetLedEnable(hCamera, index):
+ enable = c_int()
+ err_code = _sdk.CameraGetLedEnable(hCamera, index, byref(enable))
+ SetLastError(err_code)
+ return enable.value
+
+def CameraSetLedOnOff(hCamera, index, onoff):
+ err_code = _sdk.CameraSetLedOnOff(hCamera, index, onoff)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetLedOnOff(hCamera, index):
+ onoff = c_int()
+ err_code = _sdk.CameraGetLedOnOff(hCamera, index, byref(onoff))
+ SetLastError(err_code)
+ return onoff.value
+
+def CameraSetLedDuration(hCamera, index, duration):
+ err_code = _sdk.CameraSetLedDuration(hCamera, index, duration)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetLedDuration(hCamera, index):
+ duration = c_uint()
+ err_code = _sdk.CameraGetLedDuration(hCamera, index, byref(duration))
+ SetLastError(err_code)
+ return duration.value
+
+def CameraSetLedBrightness(hCamera, index, uBrightness):
+ err_code = _sdk.CameraSetLedBrightness(hCamera, index, uBrightness)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetLedBrightness(hCamera, index):
+ uBrightness = c_uint()
+ err_code = _sdk.CameraGetLedBrightness(hCamera, index, byref(uBrightness))
+ SetLastError(err_code)
+ return uBrightness.value
+
+def CameraEnableTransferRoi(hCamera, uEnableMask):
+ err_code = _sdk.CameraEnableTransferRoi(hCamera, uEnableMask)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetTransferRoi(hCamera, index, X1, Y1, X2, Y2):
+ err_code = _sdk.CameraSetTransferRoi(hCamera, index, X1, Y1, X2, Y2)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetTransferRoi(hCamera, index):
+ pX1 = c_uint()
+ pY1 = c_uint()
+ pX2 = c_uint()
+ pY2 = c_uint()
+ err_code = _sdk.CameraGetTransferRoi(hCamera, index, byref(pX1), byref(pY1), byref(pX2), byref(pY2))
+ SetLastError(err_code)
+ return (pX1.value, pY1.value, pX2.value, pY2.value)
+
+def CameraAlignMalloc(size, align = 16):
+ _sdk.CameraAlignMalloc.restype = c_void_p
+ r = _sdk.CameraAlignMalloc(size, align)
+ return r
+
+def CameraAlignFree(membuffer):
+ _sdk.CameraAlignFree(c_void_p(membuffer))
+
+def CameraSetAutoConnect(hCamera, bEnable):
+ err_code = _sdk.CameraSetAutoConnect(hCamera, bEnable)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetAutoConnect(hCamera):
+ pbEnable = c_int()
+ err_code = _sdk.CameraGetAutoConnect(hCamera, byref(pbEnable))
+ SetLastError(err_code)
+ return pbEnable.value
+
+def CameraGetReConnectCounts(hCamera):
+ puCounts = c_int()
+ err_code = _sdk.CameraGetReConnectCounts(hCamera, byref(puCounts))
+ SetLastError(err_code)
+ return puCounts.value
+
+def CameraSetSingleGrabMode(hCamera, bEnable):
+ err_code = _sdk.CameraSetSingleGrabMode(hCamera, bEnable)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetSingleGrabMode(hCamera):
+ pbEnable = c_int()
+ err_code = _sdk.CameraGetSingleGrabMode(hCamera, byref(pbEnable))
+ SetLastError(err_code)
+ return pbEnable.value
+
+def CameraRestartGrab(hCamera):
+ err_code = _sdk.CameraRestartGrab(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraEvaluateImageDefinition(hCamera, iAlgorithSel, pbyIn, pFrInfo):
+ DefinitionValue = c_double()
+ err_code = _sdk.CameraEvaluateImageDefinition(hCamera, iAlgorithSel, c_void_p(pbyIn), byref(pFrInfo), byref(DefinitionValue))
+ SetLastError(err_code)
+ return DefinitionValue.value
+
+def CameraDrawText(pRgbBuffer, pFrInfo, pFontFileName, FontWidth, FontHeight, pText, Left, Top, Width, Height, TextColor, uFlags):
+ err_code = _sdk.CameraDrawText(c_void_p(pRgbBuffer), byref(pFrInfo), _str_to_string_buffer(pFontFileName), FontWidth, FontHeight, _str_to_string_buffer(pText), Left, Top, Width, Height, TextColor, uFlags)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGigeGetIp(pCameraInfo):
+ CamIp = create_string_buffer(32)
+ CamMask = create_string_buffer(32)
+ CamGateWay = create_string_buffer(32)
+ EtIp = create_string_buffer(32)
+ EtMask = create_string_buffer(32)
+ EtGateWay = create_string_buffer(32)
+ err_code = _sdk.CameraGigeGetIp(byref(pCameraInfo), CamIp, CamMask, CamGateWay, EtIp, EtMask, EtGateWay)
+ SetLastError(err_code)
+ return (_string_buffer_to_str(CamIp), _string_buffer_to_str(CamMask), _string_buffer_to_str(CamGateWay),
+ _string_buffer_to_str(EtIp), _string_buffer_to_str(EtMask), _string_buffer_to_str(EtGateWay) )
+
+def CameraGigeSetIp(pCameraInfo, Ip, SubMask, GateWay, bPersistent):
+ err_code = _sdk.CameraGigeSetIp(byref(pCameraInfo),
+ _str_to_string_buffer(Ip), _str_to_string_buffer(SubMask), _str_to_string_buffer(GateWay), bPersistent)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGigeGetMac(pCameraInfo):
+ CamMac = create_string_buffer(32)
+ EtMac = create_string_buffer(32)
+ err_code = _sdk.CameraGigeGetMac(byref(pCameraInfo), CamMac, EtMac)
+ SetLastError(err_code)
+ return (_string_buffer_to_str(CamMac), _string_buffer_to_str(EtMac) )
+
+def CameraEnableFastResponse(hCamera):
+ err_code = _sdk.CameraEnableFastResponse(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetCorrectDeadPixel(hCamera, bEnable):
+ err_code = _sdk.CameraSetCorrectDeadPixel(hCamera, bEnable)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetCorrectDeadPixel(hCamera):
+ pbEnable = c_int()
+ err_code = _sdk.CameraGetCorrectDeadPixel(hCamera, byref(pbEnable))
+ SetLastError(err_code)
+ return pbEnable.value
+
+def CameraFlatFieldingCorrectSetEnable(hCamera, bEnable):
+ err_code = _sdk.CameraFlatFieldingCorrectSetEnable(hCamera, bEnable)
+ SetLastError(err_code)
+ return err_code
+
+def CameraFlatFieldingCorrectGetEnable(hCamera):
+ pbEnable = c_int()
+ err_code = _sdk.CameraFlatFieldingCorrectGetEnable(hCamera, byref(pbEnable))
+ SetLastError(err_code)
+ return pbEnable.value
+
+def CameraFlatFieldingCorrectSetParameter(hCamera, pDarkFieldingImage, pDarkFieldingFrInfo, pLightFieldingImage, pLightFieldingFrInfo):
+ err_code = _sdk.CameraFlatFieldingCorrectSetParameter(hCamera, c_void_p(pDarkFieldingImage), byref(pDarkFieldingFrInfo), c_void_p(pLightFieldingImage), byref(pLightFieldingFrInfo))
+ SetLastError(err_code)
+ return err_code
+
+def CameraFlatFieldingCorrectGetParameterState(hCamera):
+ pbValid = c_int()
+ pFilePath = create_string_buffer(1024)
+ err_code = _sdk.CameraFlatFieldingCorrectGetParameterState(hCamera, byref(pbValid), pFilePath)
+ SetLastError(err_code)
+ return (pbValid.value, _string_buffer_to_str(pFilePath) )
+
+def CameraFlatFieldingCorrectSaveParameterToFile(hCamera, pszFileName):
+ err_code = _sdk.CameraFlatFieldingCorrectSaveParameterToFile(hCamera, _str_to_string_buffer(pszFileName))
+ SetLastError(err_code)
+ return err_code
+
+def CameraFlatFieldingCorrectLoadParameterFromFile(hCamera, pszFileName):
+ err_code = _sdk.CameraFlatFieldingCorrectLoadParameterFromFile(hCamera, _str_to_string_buffer(pszFileName))
+ SetLastError(err_code)
+ return err_code
+
+def CameraCommonCall(hCamera, pszCall, uResultBufSize):
+ pszResult = create_string_buffer(uResultBufSize) if uResultBufSize > 0 else None
+ err_code = _sdk.CameraCommonCall(hCamera, _str_to_string_buffer(pszCall), pszResult, uResultBufSize)
+ SetLastError(err_code)
+ return _string_buffer_to_str(pszResult) if pszResult else ''
+
+def CameraSetDenoise3DParams(hCamera, bEnable, nCount, Weights):
+ assert(nCount >= 2 and nCount <= 8)
+ if Weights:
+ assert(len(Weights) == nCount)
+ WeightsNative = (c_float * nCount)(*Weights)
+ else:
+ WeightsNative = None
+ err_code = _sdk.CameraSetDenoise3DParams(hCamera, bEnable, nCount, WeightsNative)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetDenoise3DParams(hCamera):
+ bEnable = c_int()
+ nCount = c_int()
+ bUseWeight = c_int()
+ Weights = (c_float * 8)()
+ err_code = _sdk.CameraGetDenoise3DParams(hCamera, byref(bEnable), byref(nCount), byref(bUseWeight), Weights)
+ SetLastError(err_code)
+ bEnable, nCount, bUseWeight = bEnable.value, nCount.value, bUseWeight.value
+ if bUseWeight:
+ Weights = Weights[:nCount]
+ else:
+ Weights = None
+ return (bEnable, nCount, bUseWeight, Weights)
+
+def CameraManualDenoise3D(InFramesHead, InFramesData, nCount, Weights, OutFrameHead, OutFrameData):
+ assert(nCount > 0)
+ assert(len(InFramesData) == nCount)
+ assert(Weights is None or len(Weights) == nCount)
+ InFramesDataNative = (c_void_p * nCount)(*InFramesData)
+ WeightsNative = (c_float * nCount)(*Weights) if Weights else None
+ err_code = _sdk.CameraManualDenoise3D(byref(InFramesHead), InFramesDataNative, nCount, WeightsNative, byref(OutFrameHead), c_void_p(OutFrameData))
+ SetLastError(err_code)
+ return err_code
+
+def CameraCustomizeDeadPixels(hCamera, hParent):
+ err_code = _sdk.CameraCustomizeDeadPixels(hCamera, hParent)
+ SetLastError(err_code)
+ return err_code
+
+def CameraReadDeadPixels(hCamera):
+ pNumPixel = c_int()
+ err_code = _sdk.CameraReadDeadPixels(hCamera, None, None, byref(pNumPixel))
+ SetLastError(err_code)
+ if pNumPixel.value < 1:
+ return None
+ UShortArray = c_ushort * pNumPixel.value
+ pRows = UShortArray()
+ pCols = UShortArray()
+ err_code = _sdk.CameraReadDeadPixels(hCamera, pRows, pCols, byref(pNumPixel))
+ SetLastError(err_code)
+ if err_code == 0:
+ pNumPixel = pNumPixel.value
+ else:
+ pNumPixel = 0
+ return (pRows[:pNumPixel], pCols[:pNumPixel])
+
+def CameraAddDeadPixels(hCamera, pRows, pCols, NumPixel):
+ UShortArray = c_ushort * NumPixel
+ pRowsNative = UShortArray(*pRows)
+ pColsNative = UShortArray(*pCols)
+ err_code = _sdk.CameraAddDeadPixels(hCamera, pRowsNative, pColsNative, NumPixel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraRemoveDeadPixels(hCamera, pRows, pCols, NumPixel):
+ UShortArray = c_ushort * NumPixel
+ pRowsNative = UShortArray(*pRows)
+ pColsNative = UShortArray(*pCols)
+ err_code = _sdk.CameraRemoveDeadPixels(hCamera, pRowsNative, pColsNative, NumPixel)
+ SetLastError(err_code)
+ return err_code
+
+def CameraRemoveAllDeadPixels(hCamera):
+ err_code = _sdk.CameraRemoveAllDeadPixels(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSaveDeadPixels(hCamera):
+ err_code = _sdk.CameraSaveDeadPixels(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSaveDeadPixelsToFile(hCamera, sFileName):
+ err_code = _sdk.CameraSaveDeadPixelsToFile(hCamera, _str_to_string_buffer(sFileName))
+ SetLastError(err_code)
+ return err_code
+
+def CameraLoadDeadPixelsFromFile(hCamera, sFileName):
+ err_code = _sdk.CameraLoadDeadPixelsFromFile(hCamera, _str_to_string_buffer(sFileName))
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetImageBufferPriority(hCamera, wTimes, Priority):
+ pFrameInfo = tSdkFrameHead()
+ pbyBuffer = c_void_p()
+ err_code = _sdk.CameraGetImageBufferPriority(hCamera, byref(pFrameInfo), byref(pbyBuffer), wTimes, Priority)
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return (pbyBuffer.value, pFrameInfo)
+
+def CameraGetImageBufferPriorityEx(hCamera, wTimes, Priority):
+ _sdk.CameraGetImageBufferPriorityEx.restype = c_void_p
+ piWidth = c_int()
+ piHeight = c_int()
+ pFrameBuffer = _sdk.CameraGetImageBufferPriorityEx(hCamera, byref(piWidth), byref(piHeight), wTimes, Priority)
+ err_code = CAMERA_STATUS_SUCCESS if pFrameBuffer else CAMERA_STATUS_TIME_OUT
+ SetLastError(err_code)
+ if pFrameBuffer:
+ return (pFrameBuffer, piWidth.value, piHeight.value)
+ else:
+ raise CameraException(err_code)
+
+def CameraGetImageBufferPriorityEx2(hCamera, pImageData, uOutFormat, wTimes, Priority):
+ piWidth = c_int()
+ piHeight = c_int()
+ err_code = _sdk.CameraGetImageBufferPriorityEx2(hCamera, c_void_p(pImageData), uOutFormat, byref(piWidth), byref(piHeight), wTimes, Priority)
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return (piWidth.value, piHeight.value)
+
+def CameraGetImageBufferPriorityEx3(hCamera, pImageData, uOutFormat, wTimes, Priority):
+ piWidth = c_int()
+ piHeight = c_int()
+ puTimeStamp = c_uint()
+ err_code = _sdk.CameraGetImageBufferPriorityEx3(hCamera, c_void_p(pImageData), uOutFormat, byref(piWidth), byref(piHeight), byref(puTimeStamp), wTimes, Priority)
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return (piWidth.value, piHeight.value, puTimeStamp.value)
+
+def CameraClearBuffer(hCamera):
+ err_code = _sdk.CameraClearBuffer(hCamera)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSoftTriggerEx(hCamera, uFlags):
+ err_code = _sdk.CameraSoftTriggerEx(hCamera, uFlags)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetHDR(hCamera, value):
+ err_code = _sdk.CameraSetHDR(hCamera, value)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetHDR(hCamera):
+ value = c_int()
+ err_code = _sdk.CameraGetHDR(hCamera, byref(value))
+ SetLastError(err_code)
+ return value.value
+
+def CameraGetFrameID(hCamera):
+ FrameID = c_uint()
+ err_code = _sdk.CameraGetFrameID(hCamera, byref(FrameID))
+ SetLastError(err_code)
+ return FrameID.value
+
+def CameraGetFrameTimeStamp(hCamera):
+ TimeStamp = c_uint64()
+ TimeStampL = c_uint32.from_buffer(TimeStamp)
+ TimeStampH = c_uint32.from_buffer(TimeStamp, 4)
+ err_code = _sdk.CameraGetFrameTimeStamp(hCamera, byref(TimeStampL), byref(TimeStampH))
+ SetLastError(err_code)
+ return TimeStamp.value
+
+def CameraSetHDRGainMode(hCamera, value):
+ err_code = _sdk.CameraSetHDRGainMode(hCamera, value)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetHDRGainMode(hCamera):
+ value = c_int()
+ err_code = _sdk.CameraGetHDRGainMode(hCamera, byref(value))
+ SetLastError(err_code)
+ return value.value
+
+def CameraCreateDIBitmap(hDC, pFrameBuffer, pFrameHead):
+ outBitmap = c_void_p()
+ err_code = _sdk.CameraCreateDIBitmap(hDC, c_void_p(pFrameBuffer), byref(pFrameHead), byref(outBitmap))
+ SetLastError(err_code)
+ return outBitmap.value
+
+def CameraDrawFrameBuffer(pFrameBuffer, pFrameHead, hWnd, Algorithm, Mode):
+ err_code = _sdk.CameraDrawFrameBuffer(c_void_p(pFrameBuffer), byref(pFrameHead), c_void_p(hWnd), Algorithm, Mode)
+ SetLastError(err_code)
+ return err_code
+
+def CameraFlipFrameBuffer(pFrameBuffer, pFrameHead, Flags):
+ err_code = _sdk.CameraFlipFrameBuffer(c_void_p(pFrameBuffer), byref(pFrameHead), Flags)
+ SetLastError(err_code)
+ return err_code
+
+def CameraConvertFrameBufferFormat(hCamera, pInFrameBuffer, pOutFrameBuffer, outWidth, outHeight, outMediaType, pFrameHead):
+ err_code = _sdk.CameraConvertFrameBufferFormat(hCamera, c_void_p(pInFrameBuffer), c_void_p(pOutFrameBuffer), outWidth, outHeight, outMediaType, byref(pFrameHead))
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetConnectionStatusCallback(hCamera, pCallBack, pContext = 0):
+ err_code = _sdk.CameraSetConnectionStatusCallback(hCamera, pCallBack, c_void_p(pContext) )
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetLightingControllerMode(hCamera, index, mode):
+ err_code = _sdk.CameraSetLightingControllerMode(hCamera, index, mode)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetLightingControllerState(hCamera, index, state):
+ err_code = _sdk.CameraSetLightingControllerState(hCamera, index, state)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetFrameResendCount(hCamera, count):
+ err_code = _sdk.CameraSetFrameResendCount(hCamera, count)
+ SetLastError(err_code)
+ return err_code
+
+def CameraSetUndistortParams(hCamera, width, height, cameraMatrix, distCoeffs):
+ assert(len(cameraMatrix) == 4)
+ assert(len(distCoeffs) == 5)
+ cameraMatrixNative = (c_double * len(cameraMatrix))(*cameraMatrix)
+ distCoeffsNative = (c_double * len(distCoeffs))(*distCoeffs)
+ err_code = _sdk.CameraSetUndistortParams(hCamera, width, height, cameraMatrixNative, distCoeffsNative)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetUndistortParams(hCamera):
+ width = c_int()
+ height = c_int()
+ cameraMatrix = (c_double * 4)()
+ distCoeffs = (c_double * 5)()
+ err_code = _sdk.CameraGetUndistortParams(hCamera, byref(width), byref(height), cameraMatrix, distCoeffs)
+ SetLastError(err_code)
+ width, height = width.value, height.value
+ cameraMatrix = cameraMatrix[:]
+ distCoeffs = distCoeffs[:]
+ return (width, height, cameraMatrix, distCoeffs)
+
+def CameraSetUndistortEnable(hCamera, bEnable):
+ err_code = _sdk.CameraSetUndistortEnable(hCamera, bEnable)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetUndistortEnable(hCamera):
+ value = c_int()
+ err_code = _sdk.CameraGetUndistortEnable(hCamera, byref(value))
+ SetLastError(err_code)
+ return value.value
+
+def CameraCustomizeUndistort(hCamera, hParent):
+ err_code = _sdk.CameraCustomizeUndistort(hCamera, hParent)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGetEyeCount(hCamera):
+ EyeCount = c_int()
+ err_code = _sdk.CameraGetEyeCount(hCamera, byref(EyeCount))
+ SetLastError(err_code)
+ return EyeCount.value
+
+def CameraMultiEyeImageProcess(hCamera, iEyeIndex, pbyIn, pInFrInfo, pbyOut, pOutFrInfo, uOutFormat, uReserved):
+ err_code = _sdk.CameraMultiEyeImageProcess(hCamera, iEyeIndex, c_void_p(pbyIn), byref(pInFrInfo), c_void_p(pbyOut), byref(pOutFrInfo), uOutFormat, uReserved)
+ SetLastError(err_code)
+ return err_code
+
+# CameraGrabber
+
+def CameraGrabber_CreateFromDevicePage():
+ Grabber = c_void_p()
+ err_code = _sdk.CameraGrabber_CreateFromDevicePage(byref(Grabber))
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return Grabber.value
+
+def CameraGrabber_CreateByIndex(Index):
+ Grabber = c_void_p()
+ err_code = _sdk.CameraGrabber_CreateByIndex(byref(Grabber), Index)
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return Grabber.value
+
+def CameraGrabber_CreateByName(Name):
+ Grabber = c_void_p()
+ err_code = _sdk.CameraGrabber_CreateByName(byref(Grabber), _str_to_string_buffer(Name))
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return Grabber.value
+
+def CameraGrabber_Create(pDevInfo):
+ Grabber = c_void_p()
+ err_code = _sdk.CameraGrabber_Create(byref(Grabber), byref(pDevInfo))
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return Grabber.value
+
+def CameraGrabber_Destroy(Grabber):
+ err_code = _sdk.CameraGrabber_Destroy(c_void_p(Grabber))
+ SetLastError(err_code)
+ return err_code
+
+def CameraGrabber_SetHWnd(Grabber, hWnd):
+ err_code = _sdk.CameraGrabber_SetHWnd(c_void_p(Grabber), c_void_p(hWnd) )
+ SetLastError(err_code)
+ return err_code
+
+def CameraGrabber_SetPriority(Grabber, Priority):
+ err_code = _sdk.CameraGrabber_SetPriority(c_void_p(Grabber), Priority)
+ SetLastError(err_code)
+ return err_code
+
+def CameraGrabber_StartLive(Grabber):
+ err_code = _sdk.CameraGrabber_StartLive(c_void_p(Grabber))
+ SetLastError(err_code)
+ return err_code
+
+def CameraGrabber_StopLive(Grabber):
+ err_code = _sdk.CameraGrabber_StopLive(c_void_p(Grabber))
+ SetLastError(err_code)
+ return err_code
+
+def CameraGrabber_SaveImage(Grabber, TimeOut):
+ Image = c_void_p()
+ err_code = _sdk.CameraGrabber_SaveImage(c_void_p(Grabber), byref(Image), TimeOut)
+ SetLastError(err_code)
+ if err_code != 0:
+ raise CameraException(err_code)
+ return Image.value
+
+def CameraGrabber_SaveImageAsync(Grabber):
+ err_code = _sdk.CameraGrabber_SaveImageAsync(c_void_p(Grabber))
+ SetLastError(err_code)
+ return err_code
+
+def CameraGrabber_SaveImageAsyncEx(Grabber, UserData):
+ err_code = _sdk.CameraGrabber_SaveImageAsyncEx(c_void_p(Grabber), c_void_p(UserData))
+ SetLastError(err_code)
+ return err_code
+
+def CameraGrabber_SetSaveImageCompleteCallback(Grabber, Callback, Context = 0):
+ err_code = _sdk.CameraGrabber_SetSaveImageCompleteCallback(c_void_p(Grabber), Callback, c_void_p(Context))
+ SetLastError(err_code)
+ return err_code
+
+def CameraGrabber_SetFrameListener(Grabber, Listener, Context = 0):
+ err_code = _sdk.CameraGrabber_SetFrameListener(c_void_p(Grabber), Listener, c_void_p(Context))
+ SetLastError(err_code)
+ return err_code
+
+def CameraGrabber_SetRawCallback(Grabber, Callback, Context = 0):
+ err_code = _sdk.CameraGrabber_SetRawCallback(c_void_p(Grabber), Callback, c_void_p(Context))
+ SetLastError(err_code)
+ return err_code
+
+def CameraGrabber_SetRGBCallback(Grabber, Callback, Context = 0):
+ err_code = _sdk.CameraGrabber_SetRGBCallback(c_void_p(Grabber), Callback, c_void_p(Context))
+ SetLastError(err_code)
+ return err_code
+
+def CameraGrabber_GetCameraHandle(Grabber):
+ hCamera = c_int()
+ err_code = _sdk.CameraGrabber_GetCameraHandle(c_void_p(Grabber), byref(hCamera))
+ SetLastError(err_code)
+ return hCamera.value
+
+def CameraGrabber_GetStat(Grabber):
+ stat = tSdkGrabberStat()
+ err_code = _sdk.CameraGrabber_GetStat(c_void_p(Grabber), byref(stat))
+ SetLastError(err_code)
+ return stat
+
+def CameraGrabber_GetCameraDevInfo(Grabber):
+ DevInfo = tSdkCameraDevInfo()
+ err_code = _sdk.CameraGrabber_GetCameraDevInfo(c_void_p(Grabber), byref(DevInfo))
+ SetLastError(err_code)
+ return DevInfo
+
+# CameraImage
+
+def CameraImage_Create(pFrameBuffer, pFrameHead, bCopy):
+ Image = c_void_p()
+ err_code = _sdk.CameraImage_Create(byref(Image), c_void_p(pFrameBuffer), byref(pFrameHead), bCopy)
+ SetLastError(err_code)
+ return Image.value
+
+def CameraImage_CreateEmpty():
+ Image = c_void_p()
+ err_code = _sdk.CameraImage_CreateEmpty(byref(Image))
+ SetLastError(err_code)
+ return Image.value
+
+def CameraImage_Destroy(Image):
+ err_code = _sdk.CameraImage_Destroy(c_void_p(Image))
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_GetData(Image):
+ DataBuffer = c_void_p()
+ HeadPtr = c_void_p()
+ err_code = _sdk.CameraImage_GetData(c_void_p(Image), byref(DataBuffer), byref(HeadPtr))
+ SetLastError(err_code)
+ if err_code == 0:
+ return (DataBuffer.value, tSdkFrameHead.from_address(HeadPtr.value) )
+ else:
+ return (0, None)
+
+def CameraImage_GetUserData(Image):
+ UserData = c_void_p()
+ err_code = _sdk.CameraImage_GetUserData(c_void_p(Image), byref(UserData))
+ SetLastError(err_code)
+ return UserData.value
+
+def CameraImage_SetUserData(Image, UserData):
+ err_code = _sdk.CameraImage_SetUserData(c_void_p(Image), c_void_p(UserData))
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_IsEmpty(Image):
+ IsEmpty = c_int()
+ err_code = _sdk.CameraImage_IsEmpty(c_void_p(Image), byref(IsEmpty))
+ SetLastError(err_code)
+ return IsEmpty.value
+
+def CameraImage_Draw(Image, hWnd, Algorithm):
+ err_code = _sdk.CameraImage_Draw(c_void_p(Image), c_void_p(hWnd), Algorithm)
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_DrawFit(Image, hWnd, Algorithm):
+ err_code = _sdk.CameraImage_DrawFit(c_void_p(Image), c_void_p(hWnd), Algorithm)
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_DrawToDC(Image, hDC, Algorithm, xDst, yDst, cxDst, cyDst):
+ err_code = _sdk.CameraImage_DrawToDC(c_void_p(Image), c_void_p(hDC), Algorithm, xDst, yDst, cxDst, cyDst)
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_DrawToDCFit(Image, hDC, Algorithm, xDst, yDst, cxDst, cyDst):
+ err_code = _sdk.CameraImage_DrawToDCFit(c_void_p(Image), c_void_p(hDC), Algorithm, xDst, yDst, cxDst, cyDst)
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_BitBlt(Image, hWnd, xDst, yDst, cxDst, cyDst, xSrc, ySrc):
+ err_code = _sdk.CameraImage_BitBlt(c_void_p(Image), c_void_p(hWnd), xDst, yDst, cxDst, cyDst, xSrc, ySrc)
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_BitBltToDC(Image, hDC, xDst, yDst, cxDst, cyDst, xSrc, ySrc):
+ err_code = _sdk.CameraImage_BitBltToDC(c_void_p(Image), c_void_p(hDC), xDst, yDst, cxDst, cyDst, xSrc, ySrc)
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_SaveAsBmp(Image, FileName):
+ err_code = _sdk.CameraImage_SaveAsBmp(c_void_p(Image), _str_to_string_buffer(FileName))
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_SaveAsJpeg(Image, FileName, Quality):
+ err_code = _sdk.CameraImage_SaveAsJpeg(c_void_p(Image), _str_to_string_buffer(FileName), Quality)
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_SaveAsPng(Image, FileName):
+ err_code = _sdk.CameraImage_SaveAsPng(c_void_p(Image), _str_to_string_buffer(FileName))
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_SaveAsRaw(Image, FileName, Format):
+ err_code = _sdk.CameraImage_SaveAsRaw(c_void_p(Image), _str_to_string_buffer(FileName), Format)
+ SetLastError(err_code)
+ return err_code
+
+def CameraImage_IPicture(Image):
+ NewPic = c_void_p()
+ err_code = _sdk.CameraImage_IPicture(c_void_p(Image), byref(NewPic))
+ SetLastError(err_code)
+ return NewPic.value
diff --git a/lib/cfg/__init__.py b/lib/cfg/__init__.py
new file mode 100644
index 0000000..e69de29
diff --git a/lib/cfg/cfg.py b/lib/cfg/cfg.py
new file mode 100644
index 0000000..31ec928
--- /dev/null
+++ b/lib/cfg/cfg.py
@@ -0,0 +1,42 @@
+import sys
+from pathlib import Path
+import enum
+
+project_root = Path(__file__).resolve().parents[3]
+sys.path.insert(0, str(project_root))
+
+# 键定义与映射
+OBSTACLE_KEYS = ["f_l_obstacle", "f_r_obstacle", "b_l_obstacle", "b_r_obstacle"]
+RAIL_KEYS = ["f_r_rail", "b_l_rail"]
+TITLE2D_KEY = {"前2D": "front_2d", "后2D": "rear_2d"}
+MAPPING = {
+ "前左避障": "f_l_obstacle",
+ "前右避障": "f_r_obstacle",
+ "后左避障": "b_l_obstacle",
+ "后右避障": "b_r_obstacle",
+ "前右上轨": "f_r_rail",
+ "后左上轨": "b_l_rail",
+}
+
+CAMERA_3D_CFGS = project_root + "config/camera_sn.json"
+
+CAMERA_2D_CFFS = project_root + "config/2d_camera.json"
+
+# TODO: TCP服务器配置
+HOST = "0.0.0.0"
+PORT = 65444
+
+# TODO: 帧率控制配置
+PERIOD = 0.1
+
+
+class VisionMode(enum):
+ OBSTACLE_DETECTION = 1 # 前后四个3d相机开启障碍识别 测距
+ FRONT_2D_DETECTION = 2 # 前面开始2d检测相机 后面依然是距离检测
+ REAR_2D_DETECTION = 3 # 与前者相反
+ TRACK_INSPECTION = 4 # 轨道键测
+
+
+class CameraControl(enum):
+ DESTORY = 0
+ CAPTURE = 1
diff --git a/lib/gui/__init__.py b/lib/gui/__init__.py
new file mode 100644
index 0000000..e69de29
diff --git a/lib/io/__init__.py b/lib/io/__init__.py
new file mode 100644
index 0000000..e69de29
diff --git a/lib/io/process2d.py b/lib/io/process2d.py
new file mode 100644
index 0000000..7e0e0df
--- /dev/null
+++ b/lib/io/process2d.py
@@ -0,0 +1,30 @@
+from multiprocessing import Process
+from lib.camera.MindVisionCamera import MindVisionCamera
+from lib.cfg.cfg import CameraControl
+
+
+class Process2D(Process):
+ def __init__(self, cfg, in_q, out_q):
+ # 设置进程名称
+ super().__init__(name=f"3D-{cfg['title']}")
+ self.cfg = cfg
+ self.in_q = in_q
+ self.out_q = out_q
+ self.camera = MindVisionCamera(cfg["sn"])
+ self.status = 0
+ # 仅对轨道摄像头启用 TrackDetector
+
+ def run(self):
+ while True:
+ sig = self.in_q.get()
+ if sig == CameraControl.CAPTURE:
+ img = self.camera.capture()
+ self.out_q.put(img)
+ elif sig == CameraControl.DESTORY:
+ for fn in ("destroy", "close", "release"):
+ if hasattr(self.camera, fn):
+ try:
+ getattr(self.camera, fn)()
+ except:
+ pass
+ break
diff --git a/lib/io/process3d.py b/lib/io/process3d.py
new file mode 100644
index 0000000..9b57edb
--- /dev/null
+++ b/lib/io/process3d.py
@@ -0,0 +1,26 @@
+from multiprocessing import Process
+from collections import deque
+from lib.camera.ArenaCamera import ArenaCamera
+from lib.cfg.cfg import CameraControl
+
+
+class Process3D(Process):
+ def __init__(self, cfg, in_q: deque, out_q: deque):
+ # 设置进程名称
+ super().__init__(name=f"3D-{cfg['title']}")
+ self.cfg = cfg
+ self.in_q = in_q
+ self.out_q = out_q
+ self.camera = ArenaCamera(cfg["sn"])
+ self.status = 0
+ # 仅对轨道摄像头启用 TrackDetector
+
+ def run(self):
+ while True:
+ sig = self.in_q.get()
+ if sig == CameraControl.CAPTURE:
+ _, _, dep_img = self.camera.capture()
+ self.out_q.put(dep_img)
+ elif sig == CameraControl.DESTORY:
+ self.camera.destroy()
+ break
diff --git a/lib/mod/__init__.py b/lib/mod/__init__.py
new file mode 100644
index 0000000..e69de29
diff --git a/lib/presenter/__init__.py b/lib/presenter/__init__.py
new file mode 100644
index 0000000..e69de29
diff --git a/lib/presenter/presenter.py b/lib/presenter/presenter.py
new file mode 100644
index 0000000..51d5c1f
--- /dev/null
+++ b/lib/presenter/presenter.py
@@ -0,0 +1,211 @@
+from ctypes import set_errno
+import datetime
+from lib.alg.image_processing_3d import detect_obstacles_in_box
+import time
+from multiprocessing import Manager
+import json
+from lib.io import process2d
+from lib.io import process3d
+from lib.io.process3d import Process3D
+from lib.io.process2d import Process2D
+from collections import deque, OrderedDict
+import numpy as np
+import socket
+from lib.camera.ArenaCamera import ArenaCamera
+from lib.tcp.tcp_server import TcpServer
+import open3d as o3d
+from lib.cfg.cfg import (
+ CAMERA_2D_CFFS,
+ CAMERA_3D_CFGS,
+ CameraControl,
+ VisionMode,
+ HOST,
+ PORT,
+ OBSTACLE_KEYS,
+ MAPPING,
+ RAIL_KEYS,
+ TITLE2D_KEY,
+ PERIOD,
+)
+
+
+# NOTE: Presentre类
+# 1. 管理相机进程,通过往相机进程的输入队列中发送数据控制相机采集数据,没发送一次1,相机通过输出队列返回一个图片数据
+# 2. 接收Tcp客户端发送过来的数据来切换模式,根据不同的模式采集不同的图像并解析成数据
+# 3. 将解析好的数据通过TCP服务发送出去
+class Presenter:
+ def __init__(self) -> None:
+ # TODO: 初始化进程队列
+ self.mode = VisionMode.OBSTACLE_RECO
+ self.process3d_info = {}
+ self.process2d_info = {}
+ mgr = Manager()
+ with open(CAMERA_3D_CFGS, encoding="utf-8") as f:
+ cfg3d = json.load(f)["camera"]
+ for cfg in cfg3d:
+ in_q = mgr.Queue()
+ out_q = mgr.Queue()
+ pro = Process3D(cfg["sn"], in_q, out_q)
+ self.process3d_info[cfg["title"]] = pro
+ pro.start()
+
+ with open(CAMERA_2D_CFFS, encoding="utf-8") as f:
+ cfg2d = json.load(f)["camera"]
+ for cfg in cfg2d:
+ in_q = mgr.Queue()
+ out_q = mgr.Queue()
+ pro = Process2D(cfg["sn"], in_q, out_q)
+ self.process2d_info[cfg["title"]] = pro
+ pro.start()
+
+ # NOTE: 障碍物状态历史队列
+ # 前左前右障碍物距离检测
+ # 轨道检测数据历史队列
+ # 轨道数据数值历史队列
+ # 2d检测数值队列
+ self.hist_ok = {k: deque(maxlen=10) for k in OBSTACLE_KEYS}
+ self.last_d = {k: None for k in OBSTACLE_KEYS}
+ self.hist_rail = {k: deque(maxlen=5) for k in RAIL_KEYS}
+ self.last_rail = {k: {"offset": None, "angle": None} for k in RAIL_KEYS}
+ self.two_d_hist = {k: deque(maxlen=10) for k in TITLE2D_KEY.values()}
+
+ def get_camera_data(self):
+ pass
+
+ def handle_camera_3d_data(self):
+ pass
+
+ def handle_camera_2d_data(self):
+ pass
+
+ def front_mode_data_handle(self, pkt: OrderedDict):
+ pass
+
+ def rear_mode_data_handle(self, pkt: OrderedDict):
+ pass
+
+ def obstacle_mode_data_handle(self, pkt: OrderedDict):
+ """1.获取所有3d避障相机的数据"""
+ obstacle_depth_img = {}
+ for key in self.process3d_info.keys():
+ """ 过滤掉所有上轨的相机 """
+ if key.endswith("上轨"):
+ continue
+ self.process3d_info[key].in_q.put(CameraControl.CAPTURE)
+ obstacle_depth_img[key] = self.process3d_info[key].out_q().get()
+
+ """2. 通过算法处理图像数据 这段算法应该跑在进程里 """
+ for key in obstacle_depth_img.keys():
+ intrinsic = o3d.camera.PinholeCameraIntrinsic(640, 480, 474, 505, 320, 240)
+ img = o3d.geometry.Image(obstacle_depth_img[key].astype(np.float32))
+ pcd = o3d.geometry.PointCloud.create_from_depth_image(
+ img, intrinsic, depth_scale=1000.0, depth_trunc=8.0
+ )
+ # TODO: 绘制矩形区域,检测区域内障碍物
+ if key.startswith("前"):
+ box = (np.array([-1050, -600, 500]), np.array([1050, 1000, 6000]))
+ else:
+ box = (np.array([-800, -600, 800]), np.array([800, 1100, 6000]))
+ nearest, _ = detect_obstacles_in_box(pcd, box[0], box[1], 640, 480)
+ if nearest:
+ d = float(np.linalg.norm(nearest["position"]))
+ res = {"distance": round(d, 2), "status": "NG"}
+ else:
+ res = {"distance": None, "status": "OK"}
+ """ 往障碍识别状态里添加历史记录, 只保存前10帧, 以及保存上一次的距离值 """
+ ok = res["status"] == "OK"
+ self.hist_ok[MAPPING[key]].append(ok)
+ if not ok:
+ self.last_d[MAPPING[key]] = res["distance"]
+
+ def wait_rec_tcp_data(self):
+ pass
+
+ def send_tcp_data(self):
+ pass
+
+ # TODO: 对tcp发回的数据进行按行处理,并且返回一个数组(不返回了,它接收数据只是为了切换模式)
+ def rec_tcp_data_handle(self, data):
+ if data:
+ data += data.decode("utf-8", errors="ignore")
+ while "\n" in data:
+ line, data = data.split("\n", 1)
+ if not line.strip():
+ continue
+ try:
+ cmd = json.loads(line)
+ print(f"[SERVER] Cmd: {cmd}")
+ front = cmd.get("FrontCouplerSignal", False)
+ rear = cmd.get("RearCouplerSignal", False)
+ obs = cmd.get("ObstacleDetection", False)
+ if obs:
+ self.mode = VisionMode.OBSTACLE_DETECTION
+ elif front:
+ self.mode = VisionMode.FRONT_2D_DETECTION
+ elif rear:
+ self.mode = VisionMode.REAR_2D_DETECTION
+ except json.JSONDecodeError:
+ pass
+
+ def run(self):
+ # TODO: 初始化TCP服务和收收数据缓存
+ server = TcpServer(host="0.0.0.0", port=65444)
+ tcp_rec_buf = ""
+ tcp_send_buf = ""
+ pkt = OrderedDict() # tcp发送数据包
+ try:
+ server.accept_client()
+ while True:
+ # TODO: next_time 记录时钟控制帧率
+ next_time = time.perf_counter() + PERIOD
+ try:
+ # TODO: 接收tcp接收的数据,根据数据并转换模式
+ tcp_rec_buf = server.recv_data()
+ if tcp_rec_buf:
+ self.rec_tcp_data_handle(tcp_rec_buf)
+ elif not tcp_rec_buf:
+ print("Client disconnected gracefully")
+ continue
+ except ConnectionResetError:
+ print("Warring: clietn force disconnect!!! ")
+ break
+ except socket.error as e:
+ print(f"Net Error: {e}")
+ break
+
+ # 清空发送包
+ pkt.clear()
+ pkt["time_str"] = datetime.now().strftime("%Y-%m-%d %H:%M:%S")
+ # TODO: 根据模式发送不同的数据
+ if self.mode == VisionMode.OBSTACLE_DETECTION:
+ self.obstacle_mode_data_handle(pkt)
+ elif self.mode == VisionMode.FRONT_2D_DETECTION:
+ self.front_mode_data_handle(pkt)
+ elif self.mode == VisionMode.REAR_2D_DETECTION:
+ self.rear_mode_data_handle(pkt)
+
+ # TODO: tcp发送数据
+ try:
+ tcp_send_buf = (json.dumps(pkt, ensure_ascii=False) + "\n").encode()
+ except TypeError as e:
+ print(f"JSON encode failed: {e}")
+ tcp_send_buf = b"{}"
+ server.send_data(tcp_send_buf)
+
+ # TODO: 控制帧率
+ now = time.perf_counter()
+ wait = next_time - now
+ if wait > 0:
+ time.sleep(wait)
+ next_time += PERIOD
+ except KeyboardInterrupt:
+ print("KeyboardInterrupt(Ctrl+C) shutting down")
+
+ finally:
+ for key in self.process3d_info.keys():
+ self.process3d_info[key].in_q.put(0)
+ for key in self.process2d_info.keys():
+ self.process2d_info[key].in_q.put(0)
+ ArenaCamera.shutdown()
+ print("关闭连接")
+ server.close()
diff --git a/lib/tcp/__init__.py b/lib/tcp/__init__.py
new file mode 100644
index 0000000..e69de29
diff --git a/lib/tcp/tcp_server.py b/lib/tcp/tcp_server.py
new file mode 100644
index 0000000..9a8667c
--- /dev/null
+++ b/lib/tcp/tcp_server.py
@@ -0,0 +1,26 @@
+import socket
+
+
+class TcpServer:
+ def __init__(self, host="0.0.0.0", port=65444) -> None:
+ self.host = host
+ self.port = port
+ self.sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)
+ self.sock.bind((self.host, self.port))
+ self.sock.listen(1) # 允许最多一个连接(可改大)
+ print(f"Listening on {self.host}:{self.port}")
+
+ def accept_client(self):
+ self.conn, self.addr = self.sock.accept()
+ print(f"Connected by {self.addr}")
+
+ def recv_data(self, bufsize=4096):
+ data = self.conn.recv(bufsize)
+ return data
+
+ def send_data(self, data: bytes):
+ self.conn.sendall(data)
+
+ def close(self):
+ self.conn.close()
+ self.sock.close()
diff --git a/main.py b/main.py
new file mode 100644
index 0000000..4046bf3
--- /dev/null
+++ b/main.py
@@ -0,0 +1,5 @@
+from lib.presenter.presenter import Presenter
+
+if __name__ == "__main__":
+ p = Presenter()
+ p.run()
diff --git a/pyrightconfig.json b/pyrightconfig.json
new file mode 100644
index 0000000..d81a17d
--- /dev/null
+++ b/pyrightconfig.json
@@ -0,0 +1,3 @@
+{
+ "typeCheckingMode": "off"
+}
diff --git a/requirements.txt b/requirements.txt
new file mode 100644
index 0000000000000000000000000000000000000000..76f75cc9594365d5e7eb7eea55d4791dd8e4b490
GIT binary patch
literal 130
zcmezWuaqH&p@gA`ArVMd0$G_1$qdB|wm@jXpvPbg#D)w845kdc3|tJ@)#?IuWiaG3
j6o7RZ0d*LFb(ui*6ah`n0h*fxG!0}fNCn7T1F$>*WSkX8
literal 0
HcmV?d00001
diff --git a/run.sh b/run.sh
new file mode 100755
index 0000000..e69de29