commit 08bdf29c71db0c5c7445fcfa6f2a08ed6bc5f7e1 Author: leon Date: Thu Feb 20 10:45:17 2025 +0800 init diff --git a/.gitignore b/.gitignore new file mode 100644 index 0000000..60bfb20 --- /dev/null +++ b/.gitignore @@ -0,0 +1,3 @@ +lidar_driver/build/ +camera_driver/build/ +.idea/ diff --git a/aurco_3d_detect.py b/aurco_3d_detect.py new file mode 100644 index 0000000..3404847 --- /dev/null +++ b/aurco_3d_detect.py @@ -0,0 +1,802 @@ +import cv2 +print(cv2.__version__) # 4.9.0 +import open3d as o3d +print(o3d.__version__) # 0.18.0 +import numpy as np +from os import abort +import sys +sys.path.append(r"./") +from utils import Log +from config import * +import utils +import pandas as pd + + +def extend_line_3d(pt1, pt2, distance): + """ + 计算 3D 空间两个点的延长线上的一个点 + 参数: + - point1: 第一个点的坐标 (x1, y1, z1),类型为列表或数组 + - point2: 第二个点的坐标 (x2, y2, z2),类型为列表或数组 + - distance: 从第二个点延长的距离 (正值表示延长方向,负值表示反向) + 返回: + - 延长线上的点坐标 (x, y, z),类型为数组 + """ + # 转换为 NumPy 数组 + point1 = np.array(pt1) + point2 = np.array(pt2) + # 计算方向向量 + direction = point2 - point1 + # 计算方向向量的单位向量 + direction_unit = direction / np.linalg.norm(direction) + # 延长线上的点 + extended_point = point2 + distance * direction_unit + return extended_point + +def filter_cloud(pcd): + # 获取点云中的点坐标 + points = np.asarray(pcd.points) + + # 定义 x, y, z 的范围 + x_min, x_max = -2.0, 2.0 + y_min, y_max = -2.0, 2.0 + z_min, z_max = 0, global_z_max + + # 创建布尔掩膜 + mask = ( + (points[:, 0] >= x_min) & (points[:, 0] <= x_max) & + (points[:, 1] >= y_min) & (points[:, 1] <= y_max) & + (points[:, 2] >= z_min) & (points[:, 2] <= z_max) + ) + + # 应用掩膜以过滤点云 + filtered_points = points[mask] + + # 更新点云对象 + pcd.points = o3d.utility.Vector3dVector(filtered_points) + return pcd + +def sort_marks_aruco_3d(masks): + new_mask = [] + left_pt_0, left_pt_1, left_pt_2, left_pt_3 = 0,0,0,0 + delete_index = [] + coordinate_temp = [0,1,2,3] + # max_val = 0 + max_val = -999999.0 + min_val = 999999.0 + for i in range(len(masks)): + left_pt = masks[i][0] + val = left_pt[0] + left_pt[1] + if val > max_val: + left_pt_3 = i + max_val = val + if val < min_val: + left_pt_0 = i + min_val = val + delete_index.append(left_pt_0) + delete_index.append(left_pt_3) + coordinate_temp = np.delete(coordinate_temp, delete_index, axis=0) + if masks[coordinate_temp[0]][0][0] > masks[coordinate_temp[1]][0][0]: + left_pt_1 = coordinate_temp[0] + left_pt_2 = coordinate_temp[1] + else: + left_pt_2 = coordinate_temp[0] + left_pt_1 = coordinate_temp[1] + new_mask.append(masks[left_pt_0]) + new_mask.append(masks[left_pt_1]) + new_mask.append(masks[left_pt_2]) + new_mask.append(masks[left_pt_3]) + return new_mask + +def sort_marks_aruco_3d_v2(masks): + new_mask = [] + left_pt_0, left_pt_1, left_pt_2, left_pt_3 = 0,0,0,0 + delete_index = [] + coordinate_temp = [0,1,2,3] + max_val = 0 + min_val = 999999 + for i in range(len(masks)): + left_pt = masks[i][0][0] + val = left_pt[0] + left_pt[1] + if val > max_val: + left_pt_3 = i + max_val = val + if val < min_val: + left_pt_0 = i + min_val = val + delete_index.append(left_pt_0) + delete_index.append(left_pt_3) + coordinate_temp = np.delete(coordinate_temp, delete_index, axis=0) + if masks[coordinate_temp[0]][0][0][0] > masks[coordinate_temp[1]][0][0][0]: + left_pt_1 = coordinate_temp[0] + left_pt_2 = coordinate_temp[1] + else: + left_pt_2 = coordinate_temp[0] + left_pt_1 = coordinate_temp[1] + new_mask.append(masks[left_pt_0]) + new_mask.append(masks[left_pt_1]) + new_mask.append(masks[left_pt_2]) + new_mask.append(masks[left_pt_3]) + return new_mask + +def cal_camera_marks_3d_conners(file_path): + marks_3d_conners = [] + frame = cv2.imread(file_path) + if frame is None: + abort() + + # 定义使用的字典类型 + aruco_dict = cv2.aruco.getPredefinedDictionary(cv2.aruco.DICT_ARUCO_ORIGINAL) + parameters = cv2.aruco.DetectorParameters() + gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY) + + # 检测ArUco标记 + # corners, ids, rejectedImgPoints = cv2.aruco.detectMarkers(gray, aruco_dict, parameters=parameters) + aruco_detector = cv2.aruco.ArucoDetector(aruco_dict, parameters) + corners, ids, rejectedImgPoints = aruco_detector.detectMarkers(gray) + + rotation_matrices = [] + if ids is not None: + # 对角点进行亚像素级别的细化以提高精度 + criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 50, 0.0003) + for corner in corners: + cv2.cornerSubPix(gray, corner, winSize=(3, 3), zeroZone=(-1, -1), criteria=criteria) + + # 定义标记的世界坐标(假设标记位于z=0平面上) + obj_points = np.array([[-marker_size/2, -marker_size/2, 0], # 左上 + [ marker_size/2, -marker_size/2, 0], # 右上 + [ marker_size/2, marker_size/2, 0], # 右下 + [-marker_size/2, marker_size/2, 0]], dtype=np.float32) # 左下 + + # obj_points = np.array([[-marker_size/2, marker_size/2, 0], # 左下角 + # [ marker_size/2, marker_size/2, 0], # 右下角 + # [ marker_size/2, -marker_size/2, 0], # 右上角 + # [-marker_size/2, -marker_size/2, 0]], dtype=np.float32) # 左上角 + + # 遍历所有检测到的标记 + Log.info("2D->3D 通过相邻角点计算得到的边长进行对比") + for i, corner in enumerate(corners): + Log.error("2d-2d 的边长") + print(np.linalg.norm(corner[0][0] - corner[0][1]) / 0.7) + print(np.linalg.norm(corner[0][1] - corner[0][2]) / 0.7) + print(np.linalg.norm(corner[0][2] - corner[0][3]) / 0.7) + print(np.linalg.norm(corner[0][3] - corner[0][0]) / 0.7) + + conners_pcd = o3d.geometry.PointCloud() + # for j in range(4): + # conners_pcd.points.append(obj_points[j]) + + # 估计每个标记的姿态 + # _, rvec, tvec = cv2.solvePnP(obj_points, corner, camera_matrix, dist_coeffs, flags=cv2.SOLVEPNP_DLS) + + _, rvec, tvec = cv2.solvePnP(obj_points, corner, camera_matrix, dist_coeffs) + + # 绘制每个标记的轴线 + cv2.drawFrameAxes(frame, camera_matrix, dist_coeffs, rvec, tvec, 0.1) + + # 将旋转向量转换为旋转矩阵(如果需要) + rotation_matrix, _ = cv2.Rodrigues(rvec) + rotation_matrices.append(rotation_matrix) + + # 使用cv2.invert()计算矩阵的逆 + retval, rotation_matrix_inv = cv2.invert(rotation_matrix) + # if retval != 0: print("矩阵的逆为:\n", rotation_matrix_inv) + # else: print("无法计算矩阵的逆") + + H = np.eye(4) + H[:3, :3] = rotation_matrix + H[:3, 3] = tvec.flatten() + for j in range(4): + P_world = np.array([obj_points[j][0], obj_points[j][1], obj_points[j][2], 1]) + P_camera_homogeneous = H @ P_world # 齐次坐标相乘 + conners_pcd.points.append(P_camera_homogeneous[:-1]) + + # conners_pcd.rotate(rotation_matrix, (0,0,0)) + # conners_pcd.translate(tvec) + + # 在图像上绘制角点编号(可选) + for j, point in enumerate(corner[0]): + text = str(conners_pcd.points[j]) + if j == 3: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 255, 255), 10, cv2.LINE_AA) + elif j == 2: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 255, 0), 10, cv2.LINE_AA) + elif j == 1: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (255, 255, 255), 10, cv2.LINE_AA) + else: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 0, 255), 10, cv2.LINE_AA) + + + # 将点云的点转换为 NumPy 数组 + points = np.asarray(conners_pcd.points) + reversed_points = points[::-1] + conners_pcd.points = o3d.utility.Vector3dVector(reversed_points) + + # 计算角点和边长 + e1p1 = extend_line_3d(conners_pcd.points[2], conners_pcd.points[1], b2) + e1p2 = extend_line_3d(conners_pcd.points[3], conners_pcd.points[0], b2) + left2 = extend_line_3d(e1p2, e1p1 , b1) + top = extend_line_3d(e1p1, e1p2, board_size - b1 - marker_size) + + e2p1 = extend_line_3d(conners_pcd.points[1], conners_pcd.points[0], board_size - b1 - marker_size) + e2p2 = extend_line_3d(conners_pcd.points[2], conners_pcd.points[3], board_size - b1 - marker_size) + top2 = extend_line_3d(e2p2, e2p1, b2) + right = extend_line_3d(e2p1, e2p2, board_size - b2 - marker_size) + + e3p1 = extend_line_3d(conners_pcd.points[0], conners_pcd.points[3], board_size - b2 - marker_size) + e3p2 = extend_line_3d(conners_pcd.points[1], conners_pcd.points[2], board_size - b2 - marker_size) + right2 = extend_line_3d(e3p2, e3p1, board_size - b1 - marker_size) + bottom = extend_line_3d(e3p1, e3p2, b1) + + e4p1 = extend_line_3d(conners_pcd.points[3], conners_pcd.points[2], b2) + e4p2 = extend_line_3d(conners_pcd.points[0], conners_pcd.points[1], b2) + bottom2 = extend_line_3d(e4p2, e4p1, board_size - b2 - marker_size) + left = extend_line_3d(e4p1, e4p2, b2) + + print( + np.linalg.norm(left - left2), + np.linalg.norm(top - top2), + np.linalg.norm(right - right2), + np.linalg.norm(bottom - bottom2) + ) + print( + np.linalg.norm(top - left), + np.linalg.norm(right - top), + np.linalg.norm(bottom - right), + np.linalg.norm(left - bottom), + ) + marks_3d_conners.append([left, top, right, bottom]) + + marks_3d_conners = sort_marks_aruco_3d(marks_3d_conners) + # 按照左、上、右、底顺序返回 + return frame, marks_3d_conners + +def cal_camera_marks_3d_conners_v2(file_path): + marks_3d_conners = [] + frame = cv2.imread(file_path) + if frame is None: + abort() + + # 定义使用的字典类型 + aruco_dict = cv2.aruco.getPredefinedDictionary(cv2.aruco.DICT_ARUCO_ORIGINAL) + parameters = cv2.aruco.DetectorParameters() + gray = cv2.cvtColor(frame, cv2.COLOR_BGR2GRAY) + + # 检测ArUco标记 + # corners, ids, rejectedImgPoints = cv2.aruco.detectMarkers(gray, aruco_dict, parameters=parameters) + aruco_detector = cv2.aruco.ArucoDetector(aruco_dict, parameters) + corners, ids, rejectedImgPoints = aruco_detector.detectMarkers(gray) + + rotation_matrices = [] + if ids is not None: + # 对角点进行亚像素级别的细化以提高精度 + criteria = (cv2.TERM_CRITERIA_EPS + cv2.TERM_CRITERIA_MAX_ITER, 50, 0.0003) + for corner in corners: + cv2.cornerSubPix(gray, corner, winSize=(3, 3), zeroZone=(-1, -1), criteria=criteria) + + # 定义标记的世界坐标(假设标记位于z=0平面上) + obj_points = np.array([[-marker_size/2, -marker_size/2, 0], # 左上 + [ marker_size/2, -marker_size/2, 0], # 右上 + [ marker_size/2, marker_size/2, 0], # 右下 + [-marker_size/2, marker_size/2, 0]], dtype=np.float32) # 左下 + + # obj_points = np.array([[-marker_size/2, marker_size/2, 0], # 左下角 + # [ marker_size/2, marker_size/2, 0], # 右下角 + # [ marker_size/2, -marker_size/2, 0], # 右上角 + # [-marker_size/2, -marker_size/2, 0]], dtype=np.float32) # 左上角 + + # 遍历所有检测到的标记 + Log.error("2D->2D 通过相邻角点计算得到的边长进行对比") + # for i, cornner in enumerate(corners): + print(np.linalg.norm(corners[0][0][0] - corners[0][0][1])) + print(np.linalg.norm(corners[0][0][1] - corners[0][0][2])) + print(np.linalg.norm(corners[0][0][2] - corners[0][0][3])) + print(np.linalg.norm(corners[0][0][3] - corners[0][0][0])) + for i, corner in enumerate(corners): + conners_pcd = o3d.geometry.PointCloud() + # for j in range(4): + # conners_pcd.points.append(obj_points[j]) + + # 估计每个标记的姿态 + # _, rvec, tvec = cv2.solvePnP(obj_points, corner, camera_matrix, dist_coeffs, flags=cv2.SOLVEPNP_DLS) + + _, rvec, tvec = cv2.solvePnP(obj_points, corner, camera_matrix, dist_coeffs, flags=cv2.SOLVEPNP_EPNP) + + # 绘制每个标记的轴线 + cv2.drawFrameAxes(frame, camera_matrix, dist_coeffs, rvec, tvec, 0.1) + + # 将旋转向量转换为旋转矩阵(如果需要) + rotation_matrix, _ = cv2.Rodrigues(rvec) + rotation_matrices.append(rotation_matrix) + + # 使用cv2.invert()计算矩阵的逆 + retval, rotation_matrix_inv = cv2.invert(rotation_matrix) + # if retval != 0: print("矩阵的逆为:\n", rotation_matrix_inv) + # else: print("无法计算矩阵的逆") + + H = np.eye(4) + H[:3, :3] = rotation_matrix + H[:3, 3] = tvec.flatten() + for j in range(4): + P_world = np.array([obj_points[j][0], obj_points[j][1], obj_points[j][2], 1]) + P_camera_homogeneous = H @ P_world # 齐次坐标相乘 + conners_pcd.points.append(P_camera_homogeneous[:-1]) + + # conners_pcd.rotate(rotation_matrix, (0,0,0)) + # conners_pcd.translate(tvec) + + # 在图像上绘制角点编号(可选) + for j, point in enumerate(corner[0]): + text = str(conners_pcd.points[j]) + if j == 3: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 255, 255), 10, cv2.LINE_AA) + elif j == 2: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 255, 0), 10, cv2.LINE_AA) + elif j == 1: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (255, 255, 255), 10, cv2.LINE_AA) + else: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 0, 255), 10, cv2.LINE_AA) + + # 将点云的点转换为 NumPy 数组 + points = np.asarray(conners_pcd.points) + reversed_points = points[::-1] + conners_pcd.points = o3d.utility.Vector3dVector(reversed_points) + + left = conners_pcd.points[1] + top = conners_pcd.points[0] + right = conners_pcd.points[3] + bottom = conners_pcd.points[2] + # left = conners_pcd.points[3] + # top = conners_pcd.points[0] + # right = conners_pcd.points[1] + # bottom = conners_pcd.points[2] + + print( + np.linalg.norm(top - left), + np.linalg.norm(right - top), + np.linalg.norm(bottom - right), + np.linalg.norm(left - bottom), + ) + marks_3d_conners.append([left, top, right, bottom]) + + marks_3d_conners = sort_marks_aruco_3d(marks_3d_conners) + # 按照左、上、右、底顺序返回 + return frame, marks_3d_conners + + +def cal_lidar_marks_3d_conners(frame, r_file_path): + # file_path = os.path.dirname(__file__) + "\\samples\\1.png" + + frame, marks_3d_conners = [],[] + file_path = os.path.dirname(__file__) + "\\samples\\output.ply" + src_cloud_load = o3d.io.read_point_cloud(file_path) + + reflectivitys = utils.parse_custom_attribute(file_path, "reflectivity") + # file_path = os.path.dirname(__file__) + "\\samples\\output_data.ply" + # src_cloud_data = o3d.io.read_point_cloud(file_path) + + # 点云旋转 + Rx = src_cloud_load.get_rotation_matrix_from_xyz((roll, 0, 0)) + Ry = src_cloud_load.get_rotation_matrix_from_xyz((0, pitch, 0)) + Rz = src_cloud_load.get_rotation_matrix_from_xyz((0, 0, yaw)) + src_cloud_load.rotate(Rx, (1,0,0)) + src_cloud_load.rotate(Ry, (0,1,0)) + src_cloud_load.rotate(Rz, (0,0,1)) + src_cloud_load.translate(T_vector) + # o3d.visualization.draw_geometries([src_cloud_load], mesh_show_wireframe=True) + + # 点云过滤 + ## 通过距离和反射率过滤后剩下得点云数据 + filte_src_cloud_load = [] + ## 点云的反射率数据 + filte_sreflectivitys = [] + src_cloud_load_array = np.asarray(src_cloud_load.points) + index = 0 + for point_3d in src_cloud_load_array: + if -2.0 < point_3d[0] < 2.0 and -2.0 < point_3d[1] < 2.0 and point_3d[2] < global_z_max: + filte_src_cloud_load.append((point_3d[0], point_3d[1], point_3d[2])) + filte_sreflectivitys.append([reflectivitys[index]]) + index += 1 + + # 点云投影 + ## 点云投影后的2D图 + im_project = np.zeros((global_h, global_w, 3), dtype=np.uint8) + ## 点云2D和3D对应的图 + im_2d_to_3d = np.zeros((global_h, global_w, 3), dtype=np.float64) + rvec = np.array([np.array([0.]), np.array([0.]), np.array([0.])]) + tvec = np.float64([0.0, 0.0, 0.0]) + pts_2d, _ = cv2.projectPoints(np.asarray(filte_src_cloud_load), rvec, tvec, camera_matrix, dist_coeffs) + + list_pts_2d = pts_2d.tolist() + list_pts_2d = [[[int(item) for item in subsublist] for subsublist in sublist] for sublist in list_pts_2d] + list_pts_2d_all_mask = [] + for i, pt_2d in enumerate(list_pts_2d): + if 0 <= pt_2d[0][0] < global_w and 0 <= pt_2d[0][1] < global_h: + # 只挑选出反射率小于30的点 + if filte_sreflectivitys[i][0] < 30: + # 添加2D图像的像素值 + im_project[pt_2d[0][1], pt_2d[0][0]] = (255,255,255) + # 添加2D-3D映射图像的数值 + im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]] = filte_src_cloud_load[i] + # 添加2D坐标数值,这里要保持和原始数据一致的信息,所以顺序是 pt_2d[0][0], pt_2d[0][1] + list_pts_2d_all_mask.append([pt_2d[0][0], pt_2d[0][1]]) + + # 计算图像的最小值和最大值 + min_val = np.min(im_project) + max_val = np.max(im_project) + print(min_val) + print(max_val) + + # 进行膨胀操作 + kernel = cv2.getStructuringElement(cv2.MORPH_RECT, (25, 25)) + + # 计算联通区域 + im_project_delate = cv2.morphologyEx(im_project, cv2.MORPH_DILATE, kernel) + im_project_delate = cv2.cvtColor(im_project_delate, cv2.COLOR_RGB2GRAY) + _, im_project_delate_binary = cv2.threshold(im_project_delate, 128, 255, cv2.THRESH_BINARY) + + # 查找轮廓 + # 计算连通域 + num_labels, labels, stats, centroids = \ + cv2.connectedComponentsWithStats(im_project_delate_binary, connectivity=8) + + # 忽略背景组件(标签0) + sizes = stats[1:, -1] # 获取所有连通组件的面积(忽略背景) + rectangles = stats[1:, :4] # 获取所有连通组件的边界框(忽略背景) + + # 根据面积大小排序索引,并选择面积最大的前4个 + sorted_indexes_by_size = sorted(range(sizes.shape[0]), key=lambda k: sizes[k], reverse=True)[:4] + + print("面积最大的4个连通组件索引:") + print(sorted_indexes_by_size) + + # 创建一个新的与labels大小相同的数组,用于保存面积最大的4个连通组件 + filtered_labels = np.zeros_like(labels) + + for i in sorted_indexes_by_size: + filtered_labels[labels == i + 1] = i + 1 # 注意这里要加1,因为忽略了背景组件 + + # 给每个连通区域分配一种颜色 + colors = np.random.randint(0, 255, size=(len(sorted_indexes_by_size), 3), dtype=np.uint8) + + mask4_conners = [] + for i, idx in enumerate(sorted_indexes_by_size): + colored_filtered_labels = np.zeros((filtered_labels.shape[0], filtered_labels.shape[1], 1), dtype=np.uint8) + color = colors[i] + mask = (filtered_labels == idx + 1) + colored_filtered_labels[mask] = 255 + non_zero = cv2.findNonZero(colored_filtered_labels) + rect = cv2.minAreaRect(non_zero) + box = cv2.boxPoints(rect) + box = np.int0(box) + conners = utils.sort_conners_2d(list(box)) + # 4个角点拍寻 left top right bottom + mask4_conners.append(conners) + + # mask 板子排序 左上 右上 左下 右下 + mask4_conners = sort_marks_aruco_3d(mask4_conners) + ## for test mask 板子排序 左上 右上 左下 右下 + # for i in range(4): + # conners = mask4_conners[i] + # cv2.drawContours(im_project, [np.asarray(conners)], 0, (255), 10) + # im_tmp = cv2.resize(im_project, (1000, 750)) + # cv2.imshow("1", im_tmp) + # cv2.waitKey(0) + + # 初始化每个标记板的2d坐标数组和3d点云数据数组 + pts_2d_mask_list = [] + im_2d_to_3d_mask_list = [] + for i in range(4): + pts_2d_mask = [] + im_2d_to_3d_mask = np.zeros((global_h, global_w, 3), dtype=np.float64) + pts_2d_mask_list.append(pts_2d_mask) + im_2d_to_3d_mask_list.append(im_2d_to_3d_mask) + + # 按没个标记版分别归纳2d坐标数据和3d点云数据 + ## 遍历过滤后的2d点坐标数据 + for pt_index in list_pts_2d_all_mask: + for i in range(4): + conners = mask4_conners[i] + if cv2.pointPolygonTest(np.asarray(conners), (pt_index[0],pt_index[1]), False) >= 0: + # 这里要保持2D坐标的顺序,所以是pt_index[0],pt_index[1] + pts_2d_mask_list[i].append([pt_index[0], pt_index[1]]) + # im_2d_to_3d_mask_list[i].append(im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]]) + im_2d_to_3d_mask_list[i][pt_index[1], pt_index[0]] = im_2d_to_3d[pt_index[1], pt_index[0]] + break + + # 遍历4个标记板,计算每隔标记板4个角点的3D坐标 + for m in range(4): + pts_2d_mask = pts_2d_mask_list[m] + im_2d_to_3d_mask = im_2d_to_3d_mask_list[m] + H = utils.cal_H(im_2d_to_3d_mask, pts_2d_mask, pts_2d_mask) + + # 通过单应矩阵计算角点 3D 单位坐标下的数值 + H_inv = np.linalg.inv(H) + conners_pcd = o3d.geometry.PointCloud() + for i in range(4): + conner = conners[i] + x, y = conner[0], conner[1] + pts_hom = np.array([x, y, 1]) + pts_3d = np.dot(H_inv, pts_hom.T) + pts_3d = pts_3d/pts_3d[2] + conners_pcd.points.append((pts_3d[0],pts_3d[1],pts_3d[2])) + + # 生成当前标定板的点云数据 + mark_pcd = o3d.geometry.PointCloud() + for i, pt_2d in enumerate(pts_2d_mask): + mark_pcd.points.append([im_2d_to_3d[pt_2d[1], pt_2d[0]][0], + im_2d_to_3d[pt_2d[1], pt_2d[0]][1], + im_2d_to_3d[pt_2d[1], pt_2d[0]][2]]) + # 计算标定板点云拟合平面的参数,这里会受到反射率、噪声等的影响 + plane_model, inlier_cloud, inlier_pcd_correct = utils.correct_mark_cloud(mark_pcd) + # 重新计算3D角点的空间未知 + conners_pcd = utils.reproject_cloud(plane_model, conners_pcd) + + Log.info("2D标记角点,得到得边长为:") + for i in range(4): + print(np.linalg.norm(conners_pcd.points[i] - conners_pcd.points[(i+1)%4])) + + + return frame, marks_3d_conners + + +def cal_lidar_marks_3d_conner_v2(r_file_path): + marks_3d_conners = [] + file_path = r_file_path + src_cloud_load = o3d.io.read_point_cloud(file_path) + + reflectivitys = utils.parse_custom_attribute(file_path, "reflectivity") + + # 点云旋转 + Rx = src_cloud_load.get_rotation_matrix_from_xyz((roll, 0, 0)) + Ry = src_cloud_load.get_rotation_matrix_from_xyz((0, pitch, 0)) + Rz = src_cloud_load.get_rotation_matrix_from_xyz((0, 0, yaw)) + src_cloud_load.rotate(Rx, (1,0,0)) + src_cloud_load.rotate(Ry, (0,1,0)) + src_cloud_load.rotate(Rz, (0,0,1)) + src_cloud_load.translate(T_vector) + # o3d.visualization.draw_geometries([src_cloud_load], mesh_show_wireframe=True) + + # 点云过滤 + ## 通过距离和反射率过滤后剩下得点云数据 + filte_src_cloud_load = [] + ## 点云的反射率数据 + filte_sreflectivitys = [] + src_cloud_load_array = np.asarray(src_cloud_load.points) + index = 0 + for point_3d in src_cloud_load_array: + if -2.0 < point_3d[0] < 2.0 and -2.0 < point_3d[1] < 2.0 and point_3d[2] < global_z_max: + filte_src_cloud_load.append((point_3d[0], point_3d[1], point_3d[2])) + filte_sreflectivitys.append([reflectivitys[index]]) + index += 1 + + # 点云投影 + ## 点云投影后的2D图 + im_project = np.zeros((global_h, global_w, 3), dtype=np.uint8) + ## 点云2D和3D对应的图 + im_2d_to_3d = np.zeros((global_h, global_w, 3), dtype=np.float64) + rvec = np.array([np.array([0.]), np.array([0.]), np.array([0.])]) + tvec = np.float64([0.0, 0.0, 0.0]) + pts_2d, _ = cv2.projectPoints(np.asarray(filte_src_cloud_load), rvec, tvec, camera_matrix, dist_coeffs) + + list_pts_2d = pts_2d.tolist() + list_pts_2d = [[[int(item) for item in subsublist] for subsublist in sublist] for sublist in list_pts_2d] + list_pts_2d_all_mask = [] + for i, pt_2d in enumerate(list_pts_2d): + if 0 <= pt_2d[0][0] < global_w and 0 <= pt_2d[0][1] < global_h: + # 只挑选出反射率小于30的点 + if filte_sreflectivitys[i][0] < 20: + # 添加2D图像的像素值 + im_project[pt_2d[0][1], pt_2d[0][0]] = (255,255,255) + # 添加2D-3D映射图像的数值 + im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]] = filte_src_cloud_load[i] + # 添加2D坐标数值,这里要保持和原始数据一致的信息,所以顺序是 pt_2d[0][0], pt_2d[0][1] + list_pts_2d_all_mask.append([pt_2d[0][0], pt_2d[0][1]]) + + # 计算图像的最小值和最大值 + min_val = np.min(im_project) + max_val = np.max(im_project) + print(min_val) + print(max_val) + + # 进行膨胀操作 + kernel = cv2.getStructuringElement(cv2.MORPH_RECT, (17, 17)) + + # 计算联通区域 + im_project_delate = cv2.morphologyEx(im_project, cv2.MORPH_DILATE, kernel) + im_project_delate_color = im_project_delate.copy() + im_project_delate = cv2.cvtColor(im_project_delate, cv2.COLOR_RGB2GRAY) + _, im_project_delate_binary = cv2.threshold(im_project_delate, 1, 255, cv2.THRESH_BINARY) + + # 查找轮廓 + # 计算连通域 + num_labels, labels, stats, centroids = \ + cv2.connectedComponentsWithStats(im_project_delate_binary, connectivity=8) + + # 忽略背景组件(标签0) + sizes = stats[1:, -1] # 获取所有连通组件的面积(忽略背景) + rectangles = stats[1:, :4] # 获取所有连通组件的边界框(忽略背景) + + # 根据面积大小排序索引,并选择面积最大的前4个 + sorted_indexes_by_size = sorted(range(sizes.shape[0]), key=lambda k: sizes[k], reverse=True)[:4] + + print("面积最大的4个连通组件索引:") + print(sorted_indexes_by_size) + + # 创建一个新的与labels大小相同的数组,用于保存面积最大的4个连通组件 + filtered_labels = np.zeros_like(labels) + + for i in sorted_indexes_by_size: + filtered_labels[labels == i + 1] = i + 1 # 注意这里要加1,因为忽略了背景组件 + + # 给每个连通区域分配一种颜色 + colors = np.random.randint(0, 255, size=(len(sorted_indexes_by_size), 3), dtype=np.uint8) + + mask4_conners = [] + for i, idx in enumerate(sorted_indexes_by_size): + colored_filtered_labels = np.zeros((filtered_labels.shape[0], filtered_labels.shape[1], 1), dtype=np.uint8) + color = colors[i] + mask = (filtered_labels == idx + 1) + colored_filtered_labels[mask] = 255 + # 使用该区域与原图相与 + im_project_gray = cv2.cvtColor(im_project, cv2.COLOR_BGR2GRAY) + colored_filtered_labels = cv2.bitwise_and(colored_filtered_labels, im_project_gray) + non_zero = cv2.findNonZero(colored_filtered_labels) + + # conners = utils.select_and_sort_conners_2d(non_zero) + + rect = cv2.minAreaRect(non_zero) + box = cv2.boxPoints(rect) + box = np.int0(box) + conners = utils.sort_conners_2d(list(box)) + # 4个角点拍寻 left top right bottom + mask4_conners.append(conners) + + # mask 板子排序 左上 右上 左下 右下 + mask4_conners = sort_marks_aruco_3d(mask4_conners) + ## for test mask 板子排序 左上 右上 左下 右下 + for i in range(4): + conners = mask4_conners[i] + cv2.drawContours(im_project_delate_color, [np.asarray(conners)], 0, (0, 255, 0), 20) + im_tmp = cv2.resize(im_project_delate_color, (1000, 750)) + cv2.imshow("1", im_tmp) + cv2.waitKey(0) + + Log.error("3D-2D") + print(np.linalg.norm(mask4_conners[0][0] - mask4_conners[0][1])) + print(np.linalg.norm(mask4_conners[0][1] - mask4_conners[0][2])) + print(np.linalg.norm(mask4_conners[0][2] - mask4_conners[0][3])) + print(np.linalg.norm(mask4_conners[0][3] - mask4_conners[0][0])) + + obj_points = np.array([[-marker_size/2, -marker_size/2, 0], # 左上 + [ marker_size/2, -marker_size/2, 0], # 右上 + [ marker_size/2, marker_size/2, 0], # 右下 + [-marker_size/2, marker_size/2, 0]], dtype=np.float32) # 左下 + + # obj_points = np.array([[-marker_size/2, marker_size/2, 0], # 左下角 + # [ marker_size/2, marker_size/2, 0], # 右下角 + # [ marker_size/2, -marker_size/2, 0], # 右上角 + # [-marker_size/2, -marker_size/2, 0]], dtype=np.float32) # 左上角 + + # 遍历所有检测到的标记 + rotation_matrices = [] + Log.info("2D->3D 通过相邻角点计算得到的边长进行对比") + for i, corner in enumerate(mask4_conners): + conners_pcd = o3d.geometry.PointCloud() + # for j in range(4): + # conners_pcd.points.append(obj_points[j]) + # image_points = np.array([ + # [corner[0][0], corner[0][1]], + # [corner[1][0], corner[1][1]], + # [corner[2][0], corner[2][1]], + # [corner[3][0], corner[3][1]] + # ], dtype=np.float32) + + # 0123 -> 2301 + # 与objects3D坐标对齐 + image_points = np.array([ + [corner[2][0], corner[2][1]], + [corner[3][0], corner[3][1]], + [corner[0][0], corner[0][1]], + [corner[1][0], corner[1][1]], + ], dtype=np.float32) + # 估计每个标记的姿态 + # _, rvec, tvec = cv2.solvePnP(obj_points, corner, camera_matrix, dist_coeffs, flags=cv2.SOLVEPNP_DLS) + _, rvec, tvec = cv2.solvePnP(obj_points, image_points, camera_matrix, dist_coeffs, flags=cv2.SOLVEPNP_EPNP) + + frame = im_project + # 绘制每个标记的轴线 + # cv2.drawFrameAxes(frame, camera_matrix, dist_coeffs, rvec, tvec, 0.1) + + # 将旋转向量转换为旋转矩阵(如果需要) + rotation_matrix, _ = cv2.Rodrigues(rvec) + rotation_matrices.append(rotation_matrix) + + # 使用cv2.invert()计算矩阵的逆 + retval, rotation_matrix_inv = cv2.invert(rotation_matrix) + # if retval != 0: print("矩阵的逆为:\n", rotation_matrix_inv) + # else: print("无法计算矩阵的逆") + + H = np.eye(4) + H[:3, :3] = rotation_matrix + H[:3, 3] = tvec.flatten() + for j in range(4): + P_world = np.array([obj_points[j][0], obj_points[j][1], obj_points[j][2], 1]) + P_camera_homogeneous = H @ P_world # 齐次坐标相乘 + conners_pcd.points.append(P_camera_homogeneous[:-1]) + + # conners_pcd.rotate(rotation_matrix, (0,0,0)) + # conners_pcd.translate(tvec) + + # 在图像上绘制角点编号(可选) + for j, point in enumerate(image_points): + text = str(conners_pcd.points[j]) + if j == 3: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 255, 255), 10, cv2.LINE_AA) + elif j == 2: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 255, 0), 10, cv2.LINE_AA) + elif j == 1: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (255, 255, 255), 10, cv2.LINE_AA) + else: cv2.putText(frame, text, tuple(point.astype(int)), cv2.FONT_HERSHEY_SIMPLEX, 2.5, (0, 0, 255), 10, cv2.LINE_AA) + + # 将点云的点转换为 NumPy 数组 + points = np.asarray(conners_pcd.points) + reversed_points = points[::-1] + conners_pcd.points = o3d.utility.Vector3dVector(reversed_points) + + left = conners_pcd.points[3] + top = conners_pcd.points[0] + right = conners_pcd.points[1] + bottom = conners_pcd.points[2] + conners = [left, top, right, bottom] + conners = utils.sort_conners_2d(conners) + + print( + np.linalg.norm(top - left), + np.linalg.norm(right - top), + np.linalg.norm(bottom - right), + np.linalg.norm(left - bottom), + ) + # marks_3d_conners.append([left, top, right, bottom]) + marks_3d_conners.append(conners) + + marks_3d_conners = sort_marks_aruco_3d(marks_3d_conners) + # 按照左、上、右、底顺序返回 + return frame, marks_3d_conners + +import struct +def get_low_8bits(float_num): + # 把浮点数转换成一个4字节的二进制表示 + bytes_rep = struct.pack('>d', float_num) + # 解析这个二进制表示为一个整数 + int_rep = int.from_bytes(bytes_rep, 'big') + # 使用位运算取出低8位 + low_8bits = int_rep & 0xFF + return low_8bits + +def check_ply_file(filename): + with open(filename, 'r') as file: + lines = file.readlines() + + # 打印文件头部分 + print("File header:") + for line in lines[:lines.index('end_header\n') + 1]: + print(line.strip()) + + # 打印前几个数据行 + print("\nSample data rows:") + data_start_index = lines.index('end_header\n') + 1 + for i, line in enumerate(lines[data_start_index:data_start_index + 5], start=data_start_index): + print(f"Line {i}: {line.strip()}") + +if __name__ == '__main__': + ile_path = os.path.dirname(__file__) + "\\samples\\output.ply" + cal_lidar_marks_3d_conner_v2(ile_path) + + + # o3d.visualization.draw_geometries([src_cloud_load], mesh_show_wireframe=True) + + ################################# + # FILE_PATH = "./samples/calibration/1/output.png" + # frame = cv2.imread(FILE_PATH) + # if frame is None: + # exit() + # frame, marks = cal_camera_marks_3d_conners_v2(frame) + + # # frame, marks = cal_camera_marks_3d_conners(FILE_PATH) + # Log.info("2D->3D marks conners value") + # print(marks) + # frame = cv2.resize(frame, (1000, 750)) + # cv2.imshow('frame', frame) + # cv2.waitKey(0) + + # cv2.destroyAllWindows() \ No newline at end of file diff --git a/calibration_mian.py b/calibration_mian.py new file mode 100644 index 0000000..2b1d038 --- /dev/null +++ b/calibration_mian.py @@ -0,0 +1,535 @@ +# -- coding: utf-8 -- +import aurco_3d_detect as aurco3d +import cloud_3d_detect as cloud3d +import svd +import utils +import os +import sys +from utils import Log +from config import * + + +CAMERA_FILE = os.path.dirname(__file__) + "\\samples\\1\\output.png" +LIDAR_FILE = os.path.dirname(__file__) + "\\samples\\1\\output.ply" +sys.path.append(r"./") + + +_dict = [ + "LEFT", + "TOP", + "RIGHT", + "BOTTOM", +] + + +def do_calibration_with_one_sample(camera_file_path = CAMERA_FILE, lidar_file_path = LIDAR_FILE): + global CAMERA_FILE, LIDAR_FILE + if CAMERA_FILE != camera_file_path : + CAMERA_FILE = camera_file_path + if LIDAR_FILE != lidar_file_path : + LIDAR_FILE = lidar_file_path + + frame, aurco_marks_conners = aurco3d.cal_camera_marks_3d_conners(CAMERA_FILE) + + # 分割标定板 + marks_pcd = cloud3d.seg_mark_cloud(LIDAR_FILE, kk, show=False) + if len(marks_pcd) != MARK_COUNT: + return -1, None, None + pcd_marks_conners = cloud3d.cal_marks_3d_conners(show=False) + + pcd_marks_conners_new = [] + for i in range(4): + tmmp = [] + for j in range(4): + tmmp.append(pcd_marks_conners[i].points[j]) + pcd_marks_conners_new.append(tmmp) + + # 排除异常点 + __exclude = [] + while True: + __max = 0 + __min = 10 + __mean = 0 + __cnt = 0 + __conner_mean = 0 + __conner_cnt = 0 + __conners_mean_distance = [] + for i in range(16): + src_aruco_mark_conner = aurco_marks_conners[int(i/4)][i%4] + src_cloud_mark_conner = pcd_marks_conners_new[int(i/4)][i%4] + for j in range(16): + if i in __exclude or j in __exclude: + continue + dst_aruco_mark_conner = aurco_marks_conners[int(j/4)][j%4] + dst_cloud_mark_conner = pcd_marks_conners_new[int(j/4)][j%4] + aurco_distance = np.linalg.norm(src_aruco_mark_conner - dst_aruco_mark_conner) + lidar_distance = np.linalg.norm(src_cloud_mark_conner - dst_cloud_mark_conner) + diff_distance = abs(aurco_distance - lidar_distance) + if diff_distance > __max: + __max = diff_distance + if diff_distance < __min: + __min = diff_distance + __cnt += 1 + __mean += diff_distance + __conner_cnt += 1 + __conner_mean += diff_distance + # print(str(int(i/4)) + "-" + _dict[i%4] + " : " + str(int(j/4)) + "-" + _dict[j%4] + # + " = " + str(diff_distance)) + if __conner_cnt == 0: tmp=0 + else : tmp = __conner_mean/__conner_cnt + __conners_mean_distance.append(tmp) + __conner_cnt = 0 + __conner_mean = 0 + __mean = __mean/__cnt + Log.info("16点对比结果") + print("__max:" + str(__max)) + print("__min:" + str(__min)) + print("__cnt:" + str(__cnt)) + print("__mean:" + str(__mean)) + print("__conners_mean_distance:") + + # for test + # for i in range(len(__conners_mean_distance)): + # print(__conners_mean_distance[i]) + + max_index = max(enumerate(__conners_mean_distance), key=lambda x: x[1])[0] + if len(__exclude) < conf_max_exclude_num: + __exclude.append(max_index) + else: + break + + # 初始化SVD数据 + list_marks_aurco = [] + list_marks_pcd = [] + for i in range(16): + # for test + print(aurco_marks_conners[int(i/4)][i%4][0] - pcd_marks_conners_new[int(i/4)][i%4][0], + aurco_marks_conners[int(i/4)][i%4][1] - pcd_marks_conners_new[int(i/4)][i%4][1], + aurco_marks_conners[int(i/4)][i%4][2] - pcd_marks_conners_new[int(i/4)][i%4][2]) + if i in __exclude: + continue + list_marks_aurco.append(aurco_marks_conners[int(i/4)][i%4]) + list_marks_pcd.append(pcd_marks_conners_new[int(i/4)][i%4]) + + # SVD 分解得到 RT + _R, _t, _ ,_ = svd.scipy_svd(np.asarray(list_marks_pcd), np.asarray(list_marks_aurco)) + # _r, _p, _y = utils.rotation_matrix_to_euler_angles(_R) + _r, _p, _y = utils.rotation_matrix_to_rpy(_R) + print(_R) + print(_t) + print(_r, _p, _y) + + return 0, [_t[0],_t[1],_t[2]], [_r, _p, _y], __mean + +g_marks_pcd = [] +def step1_get_aruco_and_lidar_marks_and_conners( + camera_file_path = CAMERA_FILE, + lidar_file_path = LIDAR_FILE, + times = 1, + simple=True): + + global CAMERA_FILE, LIDAR_FILE, g_marks_pcd + if CAMERA_FILE != camera_file_path : + CAMERA_FILE = camera_file_path + if LIDAR_FILE != lidar_file_path : + LIDAR_FILE = lidar_file_path + + frame, aurco_marks_conners = aurco3d.cal_camera_marks_3d_conners(CAMERA_FILE) + + if simple: + # 分割标定板 + if times == 1: # 第一次执行时分割 + g_marks_pcd = cloud3d.seg_mark_cloud_simple(LIDAR_FILE, kk, show=False) + if len(g_marks_pcd) != MARK_COUNT: + return None, None + pcd_marks_conners = cloud3d.cal_marks_3d_conners_simple(g_marks_pcd, show=False) + else: + # 分割标定板 + if times == 1: # 第一次执行时分割 + g_marks_pcd = cloud3d.seg_mark_cloud(LIDAR_FILE, kk, show=False) + if len(g_marks_pcd) != MARK_COUNT: + return None, None + pcd_marks_conners = cloud3d.cal_marks_3d_conners(show=False) + + pcd_marks_conners_new = [] + for i in range(4): + tmmp = [] + for j in range(4): + tmmp.append(pcd_marks_conners[i].points[j]) + pcd_marks_conners_new.append(tmmp) + + return aurco_marks_conners, pcd_marks_conners_new + +def step1_get_aruco_and_lidar_marks_and_conners_v2( + camera_file_path = CAMERA_FILE, + lidar_file_path = LIDAR_FILE, + times = 1, + simple=True): + + global CAMERA_FILE, LIDAR_FILE, g_marks_pcd + if CAMERA_FILE != camera_file_path : + CAMERA_FILE = camera_file_path + if LIDAR_FILE != lidar_file_path : + LIDAR_FILE = lidar_file_path + + frame, aurco_marks_conners = aurco3d.cal_camera_marks_3d_conners_v2(CAMERA_FILE) + frame, pcd_marks_conners = aurco3d.cal_lidar_marks_3d_conner_v2(LIDAR_FILE) + + pcd_marks_conners_new = [] + for i in range(4): + tmmp = [] + for j in range(4): + tmmp.append(pcd_marks_conners[i][j]) + pcd_marks_conners_new.append(tmmp) + + return aurco_marks_conners, pcd_marks_conners_new + +def step2_exclude_bad_conners(aurco_marks_conners, pcd_marks_conners): + # 排除异常点 + __exclude = [] + while True: + __max = 0 + __min = 10 + __mean = 0 + __cnt = 0 + __conner_mean = 0 + __conner_cnt = 0 + __conners_mean_distance = [] + for i in range(16): + src_aruco_mark_conner = aurco_marks_conners[int(i/4)][i%4] + src_cloud_mark_conner = pcd_marks_conners[int(i/4)][i%4] + for j in range(16): + if i in __exclude or j in __exclude: + continue + dst_aruco_mark_conner = aurco_marks_conners[int(j/4)][j%4] + dst_cloud_mark_conner = pcd_marks_conners[int(j/4)][j%4] + aurco_distance = np.linalg.norm(src_aruco_mark_conner - dst_aruco_mark_conner) + lidar_distance = np.linalg.norm(src_cloud_mark_conner - dst_cloud_mark_conner) + diff_distance = abs(aurco_distance - lidar_distance) + if diff_distance > __max: + __max = diff_distance + if diff_distance < __min: + __min = diff_distance + __cnt += 1 + __mean += diff_distance + __conner_cnt += 1 + __conner_mean += diff_distance + # print(str(int(i/4)) + "-" + _dict[i%4] + " : " + str(int(j/4)) + "-" + _dict[j%4] + # + " = " + str(diff_distance)) + if __conner_cnt == 0: tmp=0 + else : tmp = __conner_mean/__conner_cnt + __conners_mean_distance.append(tmp) + __conner_cnt = 0 + __conner_mean = 0 + __mean = __mean/__cnt + Log.info("16点对比结果") + print("__max:" + str(__max)) + print("__min:" + str(__min)) + print("__cnt:" + str(__cnt)) + print("__mean:" + str(__mean)) + print("__conners_mean_distance:") + + # for test + # for i in range(len(__conners_mean_distance)): + # print(__conners_mean_distance[i]) + + max_index = max(enumerate(__conners_mean_distance), key=lambda x: x[1])[0] + if len(__exclude) < conf_max_exclude_num: + __exclude.append(max_index) + else: + break + + # 初始化SVD数据 + list_marks_aurco = [] + list_marks_pcd = [] + for i in range(16): + # for test + print(aurco_marks_conners[int(i/4)][i%4][0] - pcd_marks_conners[int(i/4)][i%4][0], + aurco_marks_conners[int(i/4)][i%4][1] - pcd_marks_conners[int(i/4)][i%4][1], + aurco_marks_conners[int(i/4)][i%4][2] - pcd_marks_conners[int(i/4)][i%4][2]) + if i in __exclude: + continue + list_marks_aurco.append(aurco_marks_conners[int(i/4)][i%4]) + list_marks_pcd.append(pcd_marks_conners[int(i/4)][i%4]) + + return list_marks_aurco, list_marks_pcd, __mean + +def step2_exclude_bad_conners_v2(aurco_marks_conners, pcd_marks_conners): + # 排除异常点 + __exclude = [] + while True: + __max = 0 + __min = 10 + __mean = 0 + __cnt = 0 + __conner_mean = 0 + __conner_cnt = 0 + __conners_mean_distance = [] + for i in range(16): + src_aruco_mark_conner = aurco_marks_conners[int(i/4)][i%4] + src_cloud_mark_conner = pcd_marks_conners[int(i/4)][i%4] + for j in range(16): + if i in __exclude or j in __exclude: + continue + dst_aruco_mark_conner = aurco_marks_conners[int(j/4)][j%4] + dst_cloud_mark_conner = pcd_marks_conners[int(j/4)][j%4] + aurco_distance = np.linalg.norm(src_aruco_mark_conner - dst_aruco_mark_conner) + lidar_distance = np.linalg.norm(src_cloud_mark_conner - dst_cloud_mark_conner) + diff_distance = abs(aurco_distance - lidar_distance) + if diff_distance > __max: + __max = diff_distance + if diff_distance < __min: + __min = diff_distance + __cnt += 1 + __mean += diff_distance + __conner_cnt += 1 + __conner_mean += diff_distance + # print(str(int(i/4)) + "-" + _dict[i%4] + " : " + str(int(j/4)) + "-" + _dict[j%4] + # + " = " + str(diff_distance)) + if __conner_cnt == 0: tmp=0 + else : tmp = __conner_mean/__conner_cnt + __conners_mean_distance.append(tmp) + __conner_cnt = 0 + __conner_mean = 0 + __mean = __mean/__cnt + Log.info("16点对比结果") + print("__max:" + str(__max)) + print("__min:" + str(__min)) + print("__cnt:" + str(__cnt)) + print("__mean:" + str(__mean)) + print("__conners_mean_distance:") + + # for test + # for i in range(len(__conners_mean_distance)): + # print(__conners_mean_distance[i]) + + max_index = max(enumerate(__conners_mean_distance), key=lambda x: x[1])[0] + if len(__exclude) < conf_max_exclude_num: + __exclude.append(max_index) + else: + break + + # 初始化SVD数据 + list_marks_aurco = [] + list_marks_pcd = [] + Log.info("16点对比结果") + for i in range(16): + # for test + print(aurco_marks_conners[int(i/4)][i%4][0] - pcd_marks_conners[int(i/4)][i%4][0], + aurco_marks_conners[int(i/4)][i%4][1] - pcd_marks_conners[int(i/4)][i%4][1], + aurco_marks_conners[int(i/4)][i%4][2] - pcd_marks_conners[int(i/4)][i%4][2]) + list_marks_aurco.append(aurco_marks_conners[int(i/4)][i%4]) + list_marks_pcd.append(pcd_marks_conners[int(i/4)][i%4]) + + return list_marks_aurco, list_marks_pcd, __mean + +import open3d as o3d +def create_spheres(points, sizes=None, color=[0, 0.706, 1]): + """ + 创建一系列球体以替代点云中的点,允许每个点有不同的大小。 + + 参数: + points: N x 3 数组,表示N个点的位置。 + sizes: N维数组或列表,表示对应点的半径大小。如果为None,则所有球体大小相同。 + color: RGB颜色值,默认是橙色。 + + 返回: + spheres: 包含所有球体的Open3D几何对象列表。 + """ + spheres = [] + if sizes is None: + sizes = [0.006] * len(points) # 如果没有提供大小,则默认所有球体大小相同 + for i, point in enumerate(points): + sphere = o3d.geometry.TriangleMesh.create_sphere(radius=sizes[i]) + sphere.translate(point) # 将球体移动到点的位置 + sphere.paint_uniform_color(color) + spheres.append(sphere) + return spheres + +def step3_cal_aruco_and_lidar_marks_rt(aurco_marks_conners, pcd_marks_conners): + # SVD 分解得到 RT + array_aurco_marks_conners = np.asarray(aurco_marks_conners) + array_pcd_marks_conners = np.asarray(pcd_marks_conners) + _R, _t, _ ,_ = svd.scipy_svd(array_pcd_marks_conners, array_aurco_marks_conners) + # _r, _p, _y = utils.rotation_matrix_to_euler_angles(_R) + _r, _p, _y = utils.rotation_matrix_to_rpy(_R) + print(_R) + print(_t) + print(_r, _p, _y) + + # for test + _pdc_rt = (_R @ np.asarray(array_pcd_marks_conners).T).T + _t + if True: + # 角点显示的圆球半径,单位(米) + spheres_2d = create_spheres(array_aurco_marks_conners[:16], None, color=[0, 0.706, 1]) + spheres_3d = create_spheres(_pdc_rt[:16], None, color=[0, 0, 0]) + points_list = [] + for i in range(len(array_aurco_marks_conners[:16])): + points_list.append(spheres_2d[i]) + points_list.append(spheres_3d[i]) + # o3d.visualization.draw_geometries(points_list) + return 0, [_t[0],_t[1],_t[2]], [_r, _p, _y] + +def calibration_by_one_samples_points(): + calibration_result = [] + bad_samples = [] + samples_path_root = os.path.dirname(__file__) + "\\samples\\calibration" + + # 标定使用的样本数量 + samples_size = 1 + # 每个样本执行的次数 + times_per_one_sample = 2 + for subdir in utils.list_subdirs(samples_path_root): + paths = utils.traverse_folder(samples_path_root + "\\" + subdir) + if len(paths) != 2: + print("[ERROR]\t Data Error Path : " + paths) + times = 0 + while times < times_per_one_sample: + times += 1 + ret, _t, _rpy, __mean = do_calibration_with_one_sample(paths[1], paths[0]) # 0 png, 1 ply + if ret != 0: + bad_samples.append(subdir) + continue + # 合并得到最终得旋转角 + _new_rpy = utils.combine_rpy(roll, pitch, yaw, _rpy[0], _rpy[1], _rpy[2]) + calibration_result.append([subdir, str(times), __mean, _t, _rpy, _new_rpy]) + samples_size -= 1 + if samples_size == 0: + break + for i in range(len(calibration_result)): + str_mean = str(calibration_result[i][2]) + str_t = str(calibration_result[i][3]) + str_ypr = str(calibration_result[i][4]) + str_new_rpy = str(calibration_result[i][5]) + print(calibration_result[i][0], calibration_result[i][1], str_mean, str_t, str_ypr, str_new_rpy) + for i in range(len(bad_samples)): + print(bad_samples[i]) + utils.save_to_json(os.path.dirname(__file__) + '\\record\\record.json', calibration_result) + + +def calibration_by_all_samples_points(samples_path_root, samples_size=1, times_per_one_sample=2): + calibration_result = [] + bad_samples = [] + all_points = [] + + # 定义总体的 aurco_marks_conners, pcd_marks_conners + aurco_marks_conners_all = [] + pcd_marks_conners_all = [] + for subdir in utils.list_subdirs(samples_path_root): + paths = utils.traverse_folder(samples_path_root + "\\" + subdir) + if len(paths) != 2: + print("[ERROR]\t Data Error Path : " + paths) + times = 0 + while times < times_per_one_sample: + times += 1 + aurco_marks_conners, pcd_marks_conners = \ + step1_get_aruco_and_lidar_marks_and_conners(paths[1], paths[0], times) # 0 png, 1 ply + if aurco_marks_conners is None: + Log.error("subdir is " + subdir + " aurco_marks_conners has ERROR") + break + aurco_marks_conners, pcd_marks_conners, __mean = \ + step2_exclude_bad_conners(aurco_marks_conners, pcd_marks_conners) + _, _t, _rpy = step3_cal_aruco_and_lidar_marks_rt(aurco_marks_conners, pcd_marks_conners) + _new_rpy = utils.combine_rpy(roll, pitch, yaw, _rpy[0], _rpy[1], _rpy[2]) + calibration_result.append([subdir, str(times), __mean, _t, _rpy, _new_rpy]) + + for it in range(len(aurco_marks_conners)): + aurco_marks_conners_all.append(aurco_marks_conners[it].tolist()) + pcd_marks_conners_all.append(pcd_marks_conners[it].tolist()) + samples_size -= 1 + if samples_size == 0: + break + + # 将多样本多次计算的综合点统一进行SVD分解 + if len(aurco_marks_conners_all) == 0: + return -1, None, None, None + _, _t, _rpy = step3_cal_aruco_and_lidar_marks_rt(aurco_marks_conners_all, pcd_marks_conners_all) + # + _new_rpy = utils.combine_rpy(roll, pitch, yaw, _rpy[0], _rpy[1], _rpy[2]) + calibration_result.append(["all", str(len(aurco_marks_conners_all)) + " & " + str(len(pcd_marks_conners_all)), \ + __mean, _t, _rpy, _new_rpy]) + + for i in range(len(calibration_result)): + str_mean = str(calibration_result[i][2]) + str_t = str(calibration_result[i][3]) + str_ypr = str(calibration_result[i][4]) + str_new_rpy = str(calibration_result[i][5]) + print(calibration_result[i][0], calibration_result[i][1], str_mean, str_t, str_ypr, str_new_rpy) + for i in range(len(bad_samples)): + print(bad_samples[i]) + utils.save_to_json(os.path.dirname(__file__) + '\\record\\record.json', calibration_result) + + all_points.append(aurco_marks_conners_all) + all_points.append(pcd_marks_conners_all) + utils.save_to_json(os.path.dirname(__file__) + '\\record\\points.json', all_points) + + return 0, _t, _rpy, __mean + +def calibration_by_all_samples_points_v2(samples_path_root, samples_size=1, times_per_one_sample=2): + calibration_result = [] + bad_samples = [] + all_points = [] + + # 定义总体的 aurco_marks_conners, pcd_marks_conners + aurco_marks_conners_all = [] + pcd_marks_conners_all = [] + for subdir in utils.list_subdirs(samples_path_root): + paths = utils.traverse_folder(samples_path_root + "\\" + subdir) + if len(paths) != 2: + print("[ERROR]\t Data Error Path : " + paths) + times = 0 + while times < times_per_one_sample: + times += 1 + aurco_marks_conners, pcd_marks_conners = \ + step1_get_aruco_and_lidar_marks_and_conners_v2(paths[1], paths[0], times) # 0 png, 1 ply + if aurco_marks_conners is None: + Log.error("subdir is " + subdir + " aurco_marks_conners has ERROR") + break + aurco_marks_conners, pcd_marks_conners, __mean = \ + step2_exclude_bad_conners(aurco_marks_conners, pcd_marks_conners) + _, _t, _rpy = step3_cal_aruco_and_lidar_marks_rt(aurco_marks_conners, pcd_marks_conners) + _new_rpy = utils.combine_rpy(roll, pitch, yaw, _rpy[0], _rpy[1], _rpy[2]) + calibration_result.append([subdir, str(times), __mean, _t, _rpy, _new_rpy]) + + for it in range(len(aurco_marks_conners)): + aurco_marks_conners_all.append(aurco_marks_conners[it].tolist()) + pcd_marks_conners_all.append(pcd_marks_conners[it].tolist()) + samples_size -= 1 + if samples_size == 0: + break + + # 将多样本多次计算的综合点统一进行SVD分解 + if len(aurco_marks_conners_all) == 0: + return -1, None, None, None + _, _t, _rpy = step3_cal_aruco_and_lidar_marks_rt(aurco_marks_conners_all, pcd_marks_conners_all) + _new_rpy = utils.combine_rpy(roll, pitch, yaw, _rpy[0], _rpy[1], _rpy[2]) + calibration_result.append(["all", str(len(aurco_marks_conners_all)) + " & " + str(len(pcd_marks_conners_all)), \ + __mean, _t, _rpy, _new_rpy]) + + for i in range(len(calibration_result)): + str_mean = str(calibration_result[i][2]) + str_t = str(calibration_result[i][3]) + str_ypr = str(calibration_result[i][4]) + str_new_rpy = str(calibration_result[i][5]) + print(calibration_result[i][0], calibration_result[i][1], str_mean, str_t, str_ypr, str_new_rpy) + for i in range(len(bad_samples)): + print(bad_samples[i]) + utils.save_to_json(os.path.dirname(__file__) + '\\record\\record.json', calibration_result) + + all_points.append(aurco_marks_conners_all) + all_points.append(pcd_marks_conners_all) + utils.save_to_json(os.path.dirname(__file__) + '\\record\\points.json', all_points) + + return 0, _t, _rpy, __mean + + +if __name__ == '__main__': + # calibration_by_one_samples_points() + samples_size = 5 + times_per_one_sample = 1 + # samples_path_root = os.path.dirname(__file__) + "\\ssh_tmp" + samples_path_root = os.path.dirname(__file__) + "\\samples\\20250214" + ret, _t, _rpy, __mean = calibration_by_all_samples_points(samples_path_root, samples_size, times_per_one_sample) + # ret, _t, _rpy, __mean = calibration_by_all_samples_points_v2(samples_path_root, samples_size, times_per_one_sample) + # rt = utils.read_from_json(os.path.dirname(__file__) + '\\record\\record.json') + # print(rt) \ No newline at end of file diff --git a/camera_driver/CMakeLists.txt b/camera_driver/CMakeLists.txt new file mode 100644 index 0000000..20f57ee --- /dev/null +++ b/camera_driver/CMakeLists.txt @@ -0,0 +1,66 @@ +cmake_minimum_required(VERSION 3.24) + +set(CMAKE_SOURCE_DIR "/home/setups/camera_driver") + +include(${CMAKE_SOURCE_DIR}/cmake/cmakebase.cmake) +include(${CMAKE_SOURCE_DIR}/cmake/project.cmake) +include(${CMAKE_SOURCE_DIR}/cmake/ss928.cmake) + +message(STATUS "========================") +message(STATUS ${CMAKE_SYSTEM_NAME}) +message(STATUS ${CMAKE_SYSTEM_PROCESSOR}) +message(STATUS "========================") + + +PROJECT(camera_driver) + +set(CMAKE_SOURCE_DIR "./") + +find_package(OpenCV 4.10) +if(NOT OpenCV_FOUND) + message(FATAL_ERROR "OpenCV > 4.10 not found.") +endif() +MESSAGE(${OpenCV_VERSION}) + +# 检测操作系统和架构 +if(CMAKE_SYSTEM_NAME STREQUAL "Linux") + if(CMAKE_SYSTEM_PROCESSOR STREQUAL "x86_64") + set(PLATFORM "linux/x64") + elseif(CMAKE_SYSTEM_PROCESSOR STREQUAL "aarch64") + set(PLATFORM "linux/aarch64") + else() + message(FATAL_ERROR "Unsupported architecture on Linux") + endif() +elseif(CMAKE_SYSTEM_NAME STREQUAL "Windows") + if(CMAKE_SIZEOF_VOID_P EQUAL 8) + set(PLATFORM "windows/x64") + else() + message(FATAL_ERROR "Unsupported architecture on Windows") + endif() +else() + message(FATAL_ERROR "Unsupported operating system") +endif() + +# 输出当前系统和架构 +message(STATUS "operating system: ${PLATFORM}") + +SET(CMAKE_RUNTIME_OUTPUT_DIRECTORY "${CMAKE_SOURCE_DIR}/output/") + +INCLUDE_DIRECTORIES( + "/include" + "/usr/include" +) +LINK_DIRECTORIES( + /usr/lib/aarch64-linux-gnu + ${CMAKE_SOURCE_DIR}/lib +) + +aux_source_directory(${CMAKE_SOURCE_DIR}/ SRCLIST) + +add_executable(${PROJECT_NAME} ${SRCLIST}) +set_target_properties(${PROJECT_NAME} PROPERTIES LINK_FLAGS "-Wl,-rpath-link,/usr/lib/aarch64-linux-gnu") +target_link_libraries(${PROJECT_NAME} ${OpenCV_LIBS} libdl-2.31.so pthread) + +add_library(CameraDriver MODULE ${SRCLIST}) +target_link_libraries(CameraDriver ${OpenCV_LIBS}) + diff --git a/camera_driver/CameraDriver.cpp b/camera_driver/CameraDriver.cpp new file mode 100644 index 0000000..d46f3d9 --- /dev/null +++ b/camera_driver/CameraDriver.cpp @@ -0,0 +1,1101 @@ +#include "CameraDriver.h" + +extern "C"{ + +// // ***********开始: 这部分处理与SDK操作相机无关,用于显示设备列表 *********** +// // ***********BEGIN: These functions are not related to API call and used to display device info*********** +// // 数据帧回调函数 +// // Data frame callback function +// static void onGetFrame(IMV_Frame* pFrame, void* pUser) +// { +// if (pFrame == NULL) +// { +// printf("pFrame is NULL\n"); +// return; +// } + +// printf("Get frame blockId = %llu\n", pFrame->frameInfo.blockId); + +// return; +// } + +static void displayDeviceInfo(IMV_DeviceList deviceInfoList) +{ + IMV_DeviceInfo* pDevInfo = NULL; + unsigned int cameraIndex = 0; + char vendorNameCat[11]; + char cameraNameCat[16]; + + // 打印Title行 + // Print title line + printf("\nIdx Type Vendor Model S/N DeviceUserID IP Address \n"); + printf("------------------------------------------------------------------------------\n"); + + for (cameraIndex = 0; cameraIndex < deviceInfoList.nDevNum; cameraIndex++) + { + pDevInfo = &deviceInfoList.pDevInfo[cameraIndex]; + // 设备列表的相机索引 最大表示字数:3 + // Camera index in device list, display in 3 characters + printf("%-3d", cameraIndex + 1); + + // 相机的设备类型(GigE,U3V,CL,PCIe) + // Camera type + switch (pDevInfo->nCameraType) + { + case typeGigeCamera:printf(" GigE");break; + case typeU3vCamera:printf(" U3V ");break; + case typeCLCamera:printf(" CL ");break; + case typePCIeCamera:printf(" PCIe");break; + default:printf(" ");break; + } + + // 制造商信息 最大表示字数:10 + // Camera vendor name, display in 10 characters + if (strlen(pDevInfo->vendorName) > 10) + { + memcpy(vendorNameCat, pDevInfo->vendorName, 7); + vendorNameCat[7] = '\0'; + strcat(vendorNameCat, "..."); + printf(" %-10.10s", vendorNameCat); + } + else + { + printf(" %-10.10s", pDevInfo->vendorName); + } + + // 相机的型号信息 最大表示字数:10 + // Camera model name, display in 10 characters + printf(" %-10.10s", pDevInfo->modelName); + + // 相机的序列号 最大表示字数:15 + // Camera serial number, display in 15 characters + printf(" %-15.15s", pDevInfo->serialNumber); + + // 自定义用户ID 最大表示字数:15 + // Camera user id, display in 15 characters + if (strlen(pDevInfo->cameraName) > 15) + { + memcpy(cameraNameCat, pDevInfo->cameraName, 12); + cameraNameCat[12] = '\0'; + strcat(cameraNameCat, "..."); + printf(" %-15.15s", cameraNameCat); + } + else + { + printf(" %-15.15s", pDevInfo->cameraName); + } + + // GigE相机时获取IP地址 + // IP address of GigE camera + if (pDevInfo->nCameraType == typeGigeCamera) + { + printf(" %s", pDevInfo->DeviceSpecificInfo.gigeDeviceInfo.ipAddress); + } + + printf("\n"); + } + + return; +} + +static char* trim(char* pStr) +{ + char* pDst = pStr; + char* pTemStr = NULL; + + if (pDst != NULL) + { + pTemStr = pDst + strlen(pStr) - 1; + while (*pDst == ' ') + { + pDst++; + } + while ((pTemStr > pDst) && (*pTemStr == ' ')) + { + *pTemStr-- = '\0'; + } + } + return pDst; +} + +static int isInputValid(char* pInpuStr) +{ + char numChar; + char* pStr = pInpuStr; + while (*pStr != '\0') + { + numChar = *pStr; + if ((numChar > '9') || (numChar < '0')) + { + return -1; + } + pStr++; + } + return 0; +} + +static unsigned int selectDevice(unsigned int cameraCnt) +{ + char inputStr[256]; + char* pTrimStr; + int inputIndex = -1; + int ret = -1; + char* find = NULL; + + printf("\nPlease input the camera index: "); + while (1) + { + memset(inputStr, 0, sizeof(inputStr)); + fgets(inputStr, sizeof(inputStr), stdin); + + // 清空输入缓存 + // clear flush + fflush(stdin); + + // fgets比gets多吃一个换行符号,取出换行符号 + // fgets eats one more line feed symbol than gets, and takes out the line feed symbol + find = strchr(inputStr, '\n'); + if (find) { *find = '\0'; } + + pTrimStr = trim(inputStr); + ret = isInputValid(pTrimStr); + if (ret == 0) + { + inputIndex = atoi(pTrimStr); + // 输入的序号从1开始 + // Input index starts from 1 + inputIndex -= 1; + if ((inputIndex >= 0) && (inputIndex < (int)cameraCnt)) + { + break; + } + } + + printf("Input invalid! Please input the camera index: "); + } + return (unsigned int)inputIndex; +} + +// ***********结束: 这部分处理与SDK操作相机无关,用于显示设备列表 *********** +// ***********END: These functions are not related to API call and used to display device info*********** +static int setSoftTriggerConf(void* libHandle, IMV_HANDLE devHandle) +{ + int ret = IMV_OK; + // 获取设置触发源为软触发函数地址 + DLL_SetEnumFeatureSymbol DLLSetEnumFeatureSymbol = (DLL_SetEnumFeatureSymbol)dlsym(libHandle, "IMV_SetEnumFeatureSymbol"); + if (NULL == DLLSetEnumFeatureSymbol) + { + printf("Get IMV_SetEnumFeatureSymbol address failed!\n"); + return ret; + } + + // 设置触发源为软触发 + ret = DLLSetEnumFeatureSymbol(devHandle, "TriggerSource", "Software"); + if (IMV_OK != ret) + { + printf("Set triggerSource value failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 设置触发器 + ret = DLLSetEnumFeatureSymbol(devHandle, "TriggerSelector", "FrameStart"); + if (IMV_OK != ret) + { + printf("Set triggerSelector value failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 设置触发模式 + ret = DLLSetEnumFeatureSymbol(devHandle, "TriggerMode", "On"); + if (IMV_OK != ret) + { + printf("Set triggerMode value failed! ErrorCode[%d]\n", ret); + return ret; + } + + return ret; +} + +static int setUnSoftTriggerConf(void* libHandle, IMV_HANDLE devHandle) +{ + int ret = IMV_OK; + // 获取设置触发源为软触发函数地址 + DLL_SetEnumFeatureSymbol DLLSetEnumFeatureSymbol = (DLL_SetEnumFeatureSymbol)dlsym(libHandle, "IMV_SetEnumFeatureSymbol"); + if (NULL == DLLSetEnumFeatureSymbol) + { + printf("Get IMV_SetEnumFeatureSymbol address failed!\n"); + return ret; + } + + // 设置触发源为软触发 + ret = DLLSetEnumFeatureSymbol(devHandle, "TriggerSource", "Software"); + if (IMV_OK != ret) + { + printf("Set triggerSource value failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 设置触发器 + ret = DLLSetEnumFeatureSymbol(devHandle, "TriggerSelector", "FrameStart"); + if (IMV_OK != ret) + { + printf("Set triggerSelector value failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 设置触发模式 + ret = DLLSetEnumFeatureSymbol(devHandle, "TriggerMode", "Off"); + if (IMV_OK != ret) + { + printf("Set triggerMode value failed! ErrorCode[%d]\n", ret); + return ret; + } + + return ret; +} + +// Image convert +static int imageConvert(void* libHandle, IMV_HANDLE devHandle, IMV_Frame frame, IMV_EPixelType convertFormat,void** data, int& w, int& h) +{ + IMV_PixelConvertParam stPixelConvertParam; + unsigned char* pDstBuf = NULL; + unsigned int nDstBufSize = 0; + int ret = IMV_OK; + FILE* hFile = NULL; + const char* pFileName = NULL; + const char* pConvertFormatStr = NULL; + + // 获取设置触发源为软触发函数地址 + DLL_PixelConvert DLLPixelConvert = (DLL_PixelConvert)dlsym(libHandle, "IMV_PixelConvert"); + if (NULL == DLLPixelConvert) + { + printf("Get IMV_PixelConvert address failed!\n"); + return -999; + } + + switch (convertFormat) + { + case gvspPixelRGB8: + nDstBufSize = sizeof(unsigned char) * frame.frameInfo.width * frame.frameInfo.height * 3; + pFileName = (const char*)"convertRGB8.bmp"; + pConvertFormatStr = (const char*)"RGB8"; + break; + case gvspPixelBGR8: + nDstBufSize = sizeof(unsigned char) * frame.frameInfo.width * frame.frameInfo.height * 3; + pFileName = (const char*)"convertBGR8.bmp"; + pConvertFormatStr = (const char*)"BGR8"; + break; + case gvspPixelBGRA8: + nDstBufSize = sizeof(unsigned char) * frame.frameInfo.width * frame.frameInfo.height * 4; + pFileName = (const char*)"convertBGRA8.bmp"; + pConvertFormatStr = (const char*)"BGRA8"; + break; + case gvspPixelMono8: + default: + nDstBufSize = sizeof(unsigned char) * frame.frameInfo.width * frame.frameInfo.height; + pFileName = (const char*)"convertMono8.bmp"; + pConvertFormatStr = (const char*)"Mono8"; + break; + } + + pDstBuf = (unsigned char*)malloc(nDstBufSize); + if (NULL == pDstBuf) + { + printf("malloc pDstBuf failed!\n"); + return -998; + } + + // 图像转换成BGR8 + // convert image to BGR8 + memset(&stPixelConvertParam, 0, sizeof(stPixelConvertParam)); + stPixelConvertParam.nWidth = frame.frameInfo.width; + stPixelConvertParam.nHeight = frame.frameInfo.height; + stPixelConvertParam.ePixelFormat = frame.frameInfo.pixelFormat; + stPixelConvertParam.pSrcData = frame.pData; + stPixelConvertParam.nSrcDataLen = frame.frameInfo.size; + stPixelConvertParam.nPaddingX = frame.frameInfo.paddingX; + stPixelConvertParam.nPaddingY = frame.frameInfo.paddingY; + stPixelConvertParam.eBayerDemosaic = demosaicNearestNeighbor; + stPixelConvertParam.eDstPixelFormat = convertFormat; + stPixelConvertParam.pDstBuf = pDstBuf; + stPixelConvertParam.nDstBufSize = nDstBufSize; + + ret = DLLPixelConvert(devHandle, &stPixelConvertParam); + if (IMV_OK == ret) + { + printf("image convert to %s successfully! nDstDataLen (%u)\n", + pConvertFormatStr, stPixelConvertParam.nDstBufSize); + memcpy(*data, stPixelConvertParam.pDstBuf, stPixelConvertParam.nHeight * stPixelConvertParam.nWidth * 3); + printf("memcpy success! %d - %d - %d \n", *data, stPixelConvertParam.nHeight, stPixelConvertParam.nWidth); + w = stPixelConvertParam.nWidth; + h = stPixelConvertParam.nHeight; + // cv::Mat im(h, w, CV_8UC3, pDstBuf); + // cv::imwrite("/home/caowei/catkin_ws/output1.png", im); + // cv::imwrite("output1.png", im); + } + else + { + printf("image convert to %s failed! ErrorCode[%d]\n", pConvertFormatStr, ret); + } + + if (pDstBuf) + { + free(pDstBuf); + pDstBuf = NULL; + } + return ret; +} + +static void sendToRos(IMV_Frame frame) +{ + IMV_FlipImageParam stFlipImageParam; + unsigned int nChannelNum = 0; + int ret = IMV_OK; + FILE* hFile = NULL; + + memset(&stFlipImageParam, 0, sizeof(stFlipImageParam)); + + if (gvspPixelBGR8 == frame.frameInfo.pixelFormat) + { + stFlipImageParam.pSrcData = frame.pData; + stFlipImageParam.nSrcDataLen = frame.frameInfo.width * frame.frameInfo.height * BGR_CHANNEL_NUM; + stFlipImageParam.ePixelFormat = frame.frameInfo.pixelFormat; + nChannelNum = BGR_CHANNEL_NUM; + } + else + { + printf("image convert to BGR8 failed! ErrorCode[%d]\n", ret); + } + + // 向ros发送/image消息 + do + { + + } while (false); + +} + +static int ret = IMV_OK; +static unsigned int cameraIndex = 0; +static IMV_HANDLE devHandle = NULL; +static void* libHandle = NULL; +static IMV_Frame frame; + + +static DLL_EnumDevices DLLEnumDevices = NULL; +static DLL_CreateHandle DLLCreateHandle = NULL; +static DLL_DestroyHandle DLLDestroyHandle = NULL; +static DLL_Open DLLOpen = NULL; +static DLL_AttachGrabbing DLLAttachGrabbing = NULL; +static DLL_StartGrabbing DLLStartGrabbing = NULL; +static DLL_StopGrabbing DLLStopGrabbing = NULL; +static DLL_Close DLLClose = NULL; +static DLL_GetFrame DLLGetFrame = NULL; +static DLL_ReleaseFrame DLLReleaseFrame = NULL; +static DLL_ClearFrameBuffer DLLClearFrameBuffer = NULL; +static DLL_ExecuteCommandFeature DLLExecuteCommandFeature = NULL; +static DLL_SetIntFeatureValue DLLSetIntFeatureValue = NULL; +static DLL_SetDoubleFeatureValue DLLSetDoubleFeatureValue = NULL; + +// static int setGrabMode(IMV_HANDLE devHandle, bool isContious) +// { +// int ret = IMV_OK; + +// // 设置触发器 +// // Set trigger selector to FrameStart +// ret = IMV_SetEnumFeatureSymbol(devHandle, "TriggerSelector", "FrameStart"); +// if (IMV_OK != ret) +// { +// printf("Set triggerSelector value failed! ErrorCode[%d]\n", ret); +// return ret; +// } + +// if (isContious) +// { +// // 关闭触发模式 +// // Set trigger mode to Off +// ret = IMV_SetEnumFeatureSymbol(devHandle, "TriggerMode", "Off"); +// if (IMV_OK != ret) +// { +// printf("Set triggerMode value failed! ErrorCode[%d]\n", ret); +// return ret; +// } +// } +// else +// { +// // 设置触发源为软触发 +// // Set trigger source to Software +// ret = IMV_SetEnumFeatureSymbol(devHandle, "TriggerSource", "Software"); +// if (IMV_OK != ret) +// { +// printf("Set triggerSource value failed! ErrorCode[%d]\n", ret); +// return ret; +// } + +// // 设置触发模式 +// // Set trigger mode to On +// ret = IMV_SetEnumFeatureSymbol(devHandle, "TriggerMode", "On"); +// if (IMV_OK != ret) +// { +// printf("Set triggerMode value failed! ErrorCode[%d]\n", ret); +// return ret; +// } +// } + +// return ret; +// } +#include +#include +#define sleep(ms) usleep(1000 * ms) + +void* executeSoftTriggerProc(void* pUserData) +{ + int ret = IMV_OK; + IMV_HANDLE devHandle = (IMV_HANDLE)pUserData; + if (NULL == devHandle) + { + return NULL; + } + + while (true) + { + ret = DLLExecuteCommandFeature(devHandle, "TriggerSoftware"); + if (IMV_OK != ret) + { + printf("Execute TriggerSoftware failed! ErrorCode[%d]\n", ret); + // 通过睡眠时间来调节帧率 + // Adjust the frame rate by sleep time + sleep(200); + continue; + } + return NULL; + } + return NULL; +} + + +// 数据帧回调函数 +// Data frame callback function +static IMV_Frame* g_pFrame = nullptr; +static void onGetFrame(IMV_Frame* pFrame, void* pUser) +{ + int ret = IMV_OK; + // unsigned int chunkDataIndex = 0; + unsigned int paramIndex = 0; + // IMV_ChunkDataInfo chunkDataInfo; + IMV_HANDLE devHandle = (IMV_HANDLE)pUser; + + if (pFrame == NULL) + { + printf("pFrame is NULL\n"); + return; + } + + printf("Get frame blockId = %llu\n", pFrame->frameInfo.blockId); + + if (!devHandle) + { + printf("devHandle is NULL!\n"); + return; + } + + g_pFrame = pFrame; + + // // 获取ChunkData数据 + // // Get ChunkData + // for (chunkDataIndex = 0; chunkDataIndex < pFrame->frameInfo.chunkCount; chunkDataIndex++) + // { + // ret = IMV_GetChunkDataByIndex(devHandle, pFrame, chunkDataIndex, &chunkDataInfo); + // if (IMV_OK != ret) + // { + // printf("Get ChunkData failed! ErrorCode[%d]\n", ret); + // continue; + // } + + // printf("chunkID = %u\n", chunkDataInfo.chunkID); + // for (paramIndex = 0; paramIndex < chunkDataInfo.nParamCnt; paramIndex++) + // { + // printf("paramName = %s\n", chunkDataInfo.pParamNameList[paramIndex].str); + // } + // printf("\n"); + // } + + return; +} + + +int camera_init() +{ + int ret = IMV_OK; + // Load SDK library +#ifdef _WIN32 + libHandle = 0; +#else + printf("Load MVSDKmd.so!\n"); + libHandle = dlopen("libMVSDK.so", RTLD_LAZY); +#endif + if (NULL == libHandle) + { + printf("Load MVSDKmd.so library failed!\n"); + return IMV_ERROR; + } + + // 获取发现设备接口函数地址 + // Get discover camera interface address + DLLEnumDevices = (DLL_EnumDevices)dlsym(libHandle, "IMV_EnumDevices"); + if (NULL == DLLEnumDevices) + { + printf("Get IMV_EnumDevices address failed!\n"); + return IMV_ERROR; + } + + + // 获取发现设备接口函数地址 + // Get discover camera interface address + //DLL_EnumDevices DLLEnumDevices = (DLL_EnumDevices)dlsym(libHandle, "IMV_EnumDevices"); + //if (NULL == DLLEnumDevices) + //{ + // printf("Get IMV_EnumDevices address failed!\n"); + // return 0; + //} + + // 获取创建设备句柄接口函数地址 + // Get create Device Handle interface address + DLLCreateHandle = (DLL_CreateHandle)dlsym(libHandle, "IMV_CreateHandle"); + if (NULL == DLLCreateHandle) + { + printf("Get IMV_CreateHandle address failed!\n"); + return IMV_ERROR; + } + + // 获取销毁设备句柄接口函数地址 + // Get destroy Device Handle interface address + DLLDestroyHandle = (DLL_DestroyHandle)dlsym(libHandle, "IMV_DestroyHandle"); + if (NULL == DLLDestroyHandle) + { + printf("Get IMV_DestroyHandle address failed!\n"); + return IMV_ERROR; + } + + // 获取打开相机接口函数地址 + // Get open camera interface address + DLLOpen = (DLL_Open)dlsym(libHandle, "IMV_Open"); + if (NULL == DLLOpen) + { + printf("Get IMV_Open address failed!\n"); + return IMV_ERROR; + } + + // 获取注册数据帧回调接口函数地址 + // Get register data frame callback interface address + DLLAttachGrabbing = (DLL_AttachGrabbing)dlsym(libHandle, "IMV_AttachGrabbing"); + if (NULL == DLLAttachGrabbing) + { + printf("Get IMV_AttachGrabbing address failed!\n"); + return IMV_ERROR; + } + + // 获取开始拉流接口函数地址 + // Get start grabbing interface address + DLLStartGrabbing = (DLL_StartGrabbing)dlsym(libHandle, "IMV_StartGrabbing"); + if (NULL == DLLStartGrabbing) + { + printf("Get IMV_StartGrabbing address failed!\n"); + return IMV_ERROR; + } + + // 获取停止拉流接口函数地址 + // Get stop grabbing interface address + DLLStopGrabbing = (DLL_StopGrabbing)dlsym(libHandle, "IMV_StopGrabbing"); + if (NULL == DLLStopGrabbing) + { + printf("Get IMV_StopGrabbing address failed!\n"); + return IMV_ERROR; + } + + // 获取 + // 获取关闭相机接口函数地址 + // Get close camera interface address + DLLClose = (DLL_Close)dlsym(libHandle, "IMV_Close"); + if (NULL == DLLClose) + { + printf("Get IMV_Close address failed!\n"); + return IMV_ERROR; + } + + // 获取获取一帧图像函数地址 + DLLGetFrame = (DLL_GetFrame)dlsym(libHandle, "IMV_GetFrame"); + if (NULL == DLLGetFrame) + { + printf("Get IMV_GetFrame address failed!\n"); + return IMV_ERROR; + } + + DLLReleaseFrame = (DLL_ReleaseFrame)dlsym(libHandle, "IMV_ReleaseFrame"); + if (NULL == DLLReleaseFrame) + { + printf("Get IMV_ReleaseFrame address failed!\n"); + return IMV_ERROR; + } + + DLLClearFrameBuffer = (DLL_ClearFrameBuffer)dlsym(libHandle, "IMV_ClearFrameBuffer"); + if (NULL == DLLClearFrameBuffer) + { + printf("Get IMV_ClearFrameBuffer address failed!\n"); + return IMV_ERROR; + } + + DLLExecuteCommandFeature = (DLL_ExecuteCommandFeature)dlsym(libHandle, "IMV_ExecuteCommandFeature"); + if (NULL == DLLExecuteCommandFeature) + { + printf("Get IMV_ExecuteCommandFeature address failed!\n"); + return IMV_ERROR; + } + + DLLSetIntFeatureValue = (DLL_SetIntFeatureValue)dlsym(libHandle, "IMV_SetIntFeatureValue"); + if (NULL == DLLSetIntFeatureValue) + { + printf("Get IMV_SetIntFeatureValue address failed!\n"); + return IMV_ERROR; + } + + DLLSetDoubleFeatureValue = (DLL_SetDoubleFeatureValue)dlsym(libHandle, "IMV_SetDoubleFeatureValue"); + if (NULL == DLLSetDoubleFeatureValue) + { + printf("Get IMV_SetDoubleFeatureValue address failed!\n"); + return IMV_ERROR; + } + + ////////////////////// 检查接口结束 + // 发现设备 + // discover camera + IMV_DeviceList deviceInfoList; + ret = DLLEnumDevices(&deviceInfoList, interfaceTypeAll); + if (IMV_OK != ret) + { + printf("Enumeration devices failed! ErrorCode[%d]\n", ret); + return ret; + } + + if (deviceInfoList.nDevNum < 1) + { + printf("no camera\n"); + return IMV_ERROR; + } + + // 打印相机基本信息(序号,类型,制造商信息,型号,序列号,用户自定义ID,IP地址) + // Print camera info (Index, Type, Vendor, Model, Serial number, DeviceUserID, IP Address) + + displayDeviceInfo(deviceInfoList); + // 选择需要连接的相机 + // Select one camera to connect to + // cameraIndex = selectDevice(deviceInfoList.nDevNum); + cameraIndex = 0; // 第一个相机 + + // 创建设备句柄 + // Create Device Handle + ret = DLLCreateHandle(&devHandle, modeByIndex, (void*)&cameraIndex); + if (IMV_OK != ret) + { + printf("Create devHandle failed! ErrorCode[%d]\n", ret); + return IMV_ERROR; + } + + return ret; +} + +int camera_start_ansyc(int epx_time, void** data, int& w, int& h, int time_out) +{ + int ret = IMV_OK; + pthread_t threadID = 0; + + // 打开相机 + ret = DLLOpen(devHandle); + if (IMV_OK != ret) + { + printf("Open camera failed! ErrorCode[%d]\n", ret); + return ret; + } + + //设置软触发模式 + ret = setSoftTriggerConf(libHandle, devHandle); + if (IMV_OK != ret) + { + printf("setSoftTriggerConf failed! ErrorCode[%d]\n", ret); + return ret; + } + + + ret = DLLSetIntFeatureValue(devHandle, "Width", 9344); + if (IMV_OK != ret) + { + printf("Set feature value Width failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLSetIntFeatureValue(devHandle, "Height", 7000); + if (IMV_OK != ret) + { + printf("Set feature value Height failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLSetIntFeatureValue(devHandle, "OffsetX", 0); + if (IMV_OK != ret) + { + printf("Set feature value OffsetX failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLSetIntFeatureValue(devHandle, "OffsetY", 0); + if (IMV_OK != ret) + { + printf("Set feature value OffsetY failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 设置属性值曝光 + // Set feature value + ret = DLLSetDoubleFeatureValue(devHandle, "ExposureTime", epx_time); + if (IMV_OK != ret) + { + printf("Set feature value failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 注册数据帧回调函数 + // Register data frame callback function + ret = DLLAttachGrabbing(devHandle, onGetFrame, (void*)devHandle); + if (IMV_OK != ret) + { + printf("Attach grabbing failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLClearFrameBuffer(devHandle); + if (IMV_OK != ret) + { + printf("DLLClearFrameBuffer failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 开始拉流 + ret = DLLStartGrabbing(devHandle); + if (IMV_OK != ret) + { + printf("Start grabbing failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 创建软触发线程 + // Create soft trigger thread + if (pthread_create(&threadID, 0, executeSoftTriggerProc, (void*)devHandle) != 0) + { + printf("Failed to create soft trigger thread!\n"); + return -1; + } + + // 取图2秒 + // get frame 2 seconds + sleep(500); + pthread_join(threadID, NULL); + + while (g_pFrame==nullptr) + { + printf("waiting frame %d \n", 0); + sleep(500); + } + + printf("width %d\n", g_pFrame->frameInfo.width); + printf("Height %d\n", g_pFrame->frameInfo.height); + + ret = imageConvert(libHandle, devHandle, *g_pFrame, gvspPixelBGR8, data, w, h); + if (IMV_OK != ret) + { + printf("imageConvert failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLStopGrabbing(devHandle); + if (IMV_OK != ret) + { + printf("Stop grabbing failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 关闭相机 + // Close camera + ret = DLLClose(devHandle); + if (IMV_OK != ret) + { + printf("Close camera failed! ErrorCode[%d]\n", ret); + return ret; + } + printf("Close camera success! ErrorCode[%d]\n", ret); + + // Destroy Device Handle + if (NULL != devHandle) + { + // 销毁设备句柄 + // Destroy Device Handle + DLLDestroyHandle(devHandle); + } + printf("DLLDestroyHandle success! [%d]\n", ret); + + if (NULL != libHandle) + { + dlclose(libHandle); + } + printf("dlclose success! [%d]\n", 0); + + // printf("end...\n"); + return ret; +} + +int camera_start(int epx_time) +{ + int ret = IMV_OK; + + // 打开相机 + ret = DLLOpen(devHandle); + if (IMV_OK != ret) + { + printf("Open camera failed! ErrorCode[%d]\n", ret); + return ret; + } + + //设置软触发模式 !!! + ret = setSoftTriggerConf(libHandle, devHandle); + if (IMV_OK != ret) + { + printf("setSoftTriggerConf failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLSetIntFeatureValue(devHandle, "Width", 9344); + if (IMV_OK != ret) + { + printf("Set feature value Width failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLSetIntFeatureValue(devHandle, "Height", 7000); + if (IMV_OK != ret) + { + printf("Set feature value Height failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLSetIntFeatureValue(devHandle, "OffsetX", 0); + if (IMV_OK != ret) + { + printf("Set feature value OffsetX failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLSetIntFeatureValue(devHandle, "OffsetY", 0); + if (IMV_OK != ret) + { + printf("Set feature value OffsetY failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 设置属性值曝光 + // Set feature value + ret = DLLSetDoubleFeatureValue(devHandle, "ExposureTime", epx_time); + if (IMV_OK != ret) + { + printf("Set feature value failed! ErrorCode[%d]\n", ret); + return ret; + } + + //设置软触发模式 !!! + ret = setUnSoftTriggerConf(libHandle, devHandle); + if (IMV_OK != ret) + { + printf("setSoftTriggerConf failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 开始拉流 + ret = DLLStartGrabbing(devHandle); + if (IMV_OK != ret) + { + printf("Start grabbing failed! ErrorCode[%d]\n", ret); + return ret; + } + + return ret; +} + + +int camera_cap(void** data, int& w, int& h, int time_out) +{ + int ret = IMV_OK; + + + // 清除帧数据缓存 + ret = DLLClearFrameBuffer(devHandle); + if (IMV_OK != ret) + { + printf("Clear frame buffer failed! ErrorCode[%d]\n", ret); + return ret; + } + sleep(200); + + // //设置软触发模式 + // ret = setSoftTriggerConf(libHandle, devHandle); + // if (IMV_OK != ret) + // { + // printf("setSoftTriggerConf failed! ErrorCode[%d]\n", ret); + // return ret; + // } + // sleep(100); + + //软触发 + // while (true) + // { + // ret = DLLExecuteCommandFeature(devHandle, "TriggerSoftware"); + // if (IMV_OK != ret) + // { + // printf("Execute TriggerSoftware failed! ErrorCode[%d]\n", ret); + // sleep(200); + // continue; + // } + // printf("Execute TriggerSoftware success! [%d]\n", ret); + // break; + // } + sleep(2500); + + // 获取一帧图像, TIMEOUT 5000ms + ret = DLLGetFrame(devHandle, &frame, time_out); + if (IMV_OK != ret) + { + printf("Get frame failed! ErrorCode[%d]\n", ret); + return ret; + } + + printf("width %d\n", frame.frameInfo.width); + printf("Height %d\n", frame.frameInfo.height); + + ret = imageConvert(libHandle, devHandle, frame, gvspPixelBGR8, data, w, h); + if (IMV_OK != ret) + { + printf("imageConvert failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 释放图像缓存 + ret = DLLReleaseFrame(devHandle, &frame); + if (IMV_OK != ret) + { + printf("Release frame failed! ErrorCode[%d]\n", ret); + return ret; + } + + + return ret; +} + +int camera_stop() +{ + int ret = IMV_OK; + //设置软触发模式 + ret = setUnSoftTriggerConf(libHandle, devHandle); + if (IMV_OK != ret) + { + printf("setSoftTriggerConf failed! ErrorCode[%d]\n", ret); + return ret; + } + sleep(100); + + ret = DLLStopGrabbing(devHandle); + if (IMV_OK != ret) + { + printf("Stop grabbing failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 关闭相机 + // Close camera + ret = DLLClose(devHandle); + if (IMV_OK != ret) + { + printf("Close camera failed! ErrorCode[%d]\n", ret); + return ret; + } + printf("Close camera success! [%d]\n", ret); + + if (NULL != devHandle) + { + // 销毁设备句柄 + // Destroy Device Handle + DLLDestroyHandle(devHandle); + } + printf("DLLDestroyHandle success! [%d]\n", ret); + + if (NULL != libHandle) + { + dlclose(libHandle); + } + printf("dlclose success! [%d]\n", 0); + return ret; +} + +#include // 包含atoi函数 +int main(int argc, char *argv[]) +{ + if (argc == 0) + { + printf("argc == 0 [%d]\n", -1); + } + + // std::string s(argv[0]); + // std::cout << "Usage: " << argv[1] << " " << std::endl; + int ext = atoi(argv[1]); + if (ext < 10000) + { + printf("ex_time is too small == [%d]\n", ext); + return -1; + } + printf("ex_time == [%d]\n", ext); + + char* data = (char*)malloc(9344*7000*3); + int w, h; + + ret = camera_init(); + if (ret != IMV_OK) return ret; + + // ret = camera_start_ansyc(ext, (void**) &data, w, h, 5000); + // if (ret != IMV_OK) return ret; + + ret = camera_start(ext); + if (ret != IMV_OK) return ret; + + int count = 0; + while (true) + { + ret = camera_cap((void**) &data, w, h, 5000); + // if (ret != IMV_OK) return ret; + if (ret != IMV_OK) + { + count++; + continue; + } + cv::Mat im(h,w, CV_8UC3, data); + cv::imwrite("output.png", im); + + printf("cap times == [%d]\n", count); + break; + } + + camera_stop(); + + + if (data) + free(data); + return ret; +} + + +} \ No newline at end of file diff --git a/camera_driver/CameraDriver.h b/camera_driver/CameraDriver.h new file mode 100644 index 0000000..8383d82 --- /dev/null +++ b/camera_driver/CameraDriver.h @@ -0,0 +1,99 @@ +#include +#include +#include +#ifndef _WIN32 +#include +#include +#include +#endif // !_WIN32 +#include "IMVApi.h" +#include "IMVDefines.h" + +#include +#include + +extern "C"{ + +#define MONO_CHANNEL_NUM 1 +#define RGB_CHANNEL_NUM 3 +#define BGR_CHANNEL_NUM 3 + +#define sleep(ms) usleep(1000 * ms) + +typedef const char* (IMV_CALL * DLL_GetVersion) (); +typedef int (IMV_CALL * DLL_EnumDevices) (OUT IMV_DeviceList *pDeviceList, IN unsigned int interfaceType); +typedef int (IMV_CALL * DLL_EnumDevicesByUnicast) (OUT IMV_DeviceList *pDeviceList, IN const char* pIpAddress); +typedef int (IMV_CALL * DLL_CreateHandle) (OUT IMV_HANDLE* handle, IN IMV_ECreateHandleMode mode, IN void* pIdentifier); +typedef int (IMV_CALL * DLL_DestroyHandle) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_GetDeviceInfo) (IN IMV_HANDLE handle, OUT IMV_DeviceInfo *pDevInfo); +typedef int (IMV_CALL * DLL_Open) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_OpenEx) (IN IMV_HANDLE handle, IN IMV_ECameraAccessPermission accessPermission); +typedef bool (IMV_CALL * DLL_IsOpen) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_Close) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_GIGE_ForceIpAddress) (IN IMV_HANDLE handle, IN const char* pIpAddress, IN const char* pSubnetMask, IN const char* pGateway); +typedef int (IMV_CALL * DLL_GIGE_GetAccessPermission) (IN IMV_HANDLE handle, IMV_ECameraAccessPermission* pAccessPermission); +typedef int (IMV_CALL * DLL_GIGE_SetAnswerTimeout) (IN IMV_HANDLE handle, IN unsigned int timeout); +typedef int (IMV_CALL * DLL_DownLoadGenICamXML) (IN IMV_HANDLE handle, IN const char* pFullFileName); +typedef int (IMV_CALL * DLL_SaveDeviceCfg) (IN IMV_HANDLE handle, IN const char* pFullFileName); +typedef int (IMV_CALL * DLL_LoadDeviceCfg) (IN IMV_HANDLE handle, IN const char* pFullFileName, OUT IMV_ErrorList* pErrorList); +typedef int (IMV_CALL * DLL_WriteUserPrivateData) (IN IMV_HANDLE handle, IN void* pBuffer, IN_OUT unsigned int* pLength); +typedef int (IMV_CALL * DLL_ReadUserPrivateData) (IN IMV_HANDLE handle, OUT void* pBuffer, IN_OUT unsigned int* pLength); +typedef int (IMV_CALL * DLL_WriteUARTData) (IN IMV_HANDLE handle, IN void* pBuffer, IN_OUT unsigned int* pLength); +typedef int (IMV_CALL * DLL_ReadUARTData) (IN IMV_HANDLE handle, OUT void* pBuffer, IN_OUT unsigned int* pLength); +typedef int (IMV_CALL * DLL_SubscribeConnectArg) (IN IMV_HANDLE handle, IN IMV_ConnectCallBack proc, IN void* pUser); +typedef int (IMV_CALL * DLL_SubscribeParamUpdateArg) (IN IMV_HANDLE handle, IN IMV_ParamUpdateCallBack proc, IN void* pUser); +typedef int (IMV_CALL * DLL_SubscribeStreamArg) (IN IMV_HANDLE handle, IN IMV_StreamCallBack proc, IN void* pUser); +typedef int (IMV_CALL * DLL_SubscribeMsgChannelArg) (IN IMV_HANDLE handle, IN IMV_MsgChannelCallBack proc, IN void* pUser); +typedef int (IMV_CALL * DLL_SetBufferCount) (IN IMV_HANDLE handle, IN unsigned int nSize); +typedef int (IMV_CALL * DLL_ClearFrameBuffer) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_GIGE_SetInterPacketTimeout) (IN IMV_HANDLE handle, IN unsigned int nTimeout); +typedef int (IMV_CALL * DLL_GIGE_SetSingleResendMaxPacketNum) (IN IMV_HANDLE handle, IN unsigned int maxPacketNum); +typedef int (IMV_CALL * DLL_GIGE_SetMaxLostPacketNum) (IN IMV_HANDLE handle, IN unsigned int maxLostPacketNum); +typedef int (IMV_CALL * DLL_StartGrabbing) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_StartGrabbingEx) (IN IMV_HANDLE handle, IN uint64_t maxImagesGrabbed, IN IMV_EGrabStrategy strategy); +typedef bool (IMV_CALL * DLL_IsGrabbing) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_StopGrabbing) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_AttachGrabbing) (IN IMV_HANDLE handle, IN IMV_FrameCallBack proc, IN void* pUser); +typedef int (IMV_CALL * DLL_GetFrame) (IN IMV_HANDLE handle, OUT IMV_Frame* pFrame, IN unsigned int timeoutMS); +typedef int (IMV_CALL * DLL_ReleaseFrame) (IN IMV_HANDLE handle, IN IMV_Frame* pFrame); +typedef int (IMV_CALL * DLL_CloneFrame) (IN IMV_HANDLE handle, IN IMV_Frame* pFrame, OUT IMV_Frame* pCloneFrame); +typedef int (IMV_CALL * DLL_GetChunkDataByIndex) (IN IMV_HANDLE handle, IN IMV_Frame* pFrame, IN unsigned int index, OUT IMV_ChunkDataInfo *pChunkDataInfo); +typedef int (IMV_CALL * DLL_GetStatisticsInfo) (IN IMV_HANDLE handle, OUT IMV_StreamStatisticsInfo* pStreamStatsInfo); +typedef int (IMV_CALL * DLL_ResetStatisticsInfo) (IN IMV_HANDLE handle); +typedef bool (IMV_CALL * DLL_FeatureIsAvailable) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef bool (IMV_CALL * DLL_FeatureIsReadable) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef bool (IMV_CALL * DLL_FeatureIsWriteable) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef bool (IMV_CALL * DLL_FeatureIsStreamable) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef bool (IMV_CALL * DLL_FeatureIsValid) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef int (IMV_CALL * DLL_GetIntFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); +typedef int (IMV_CALL * DLL_GetIntFeatureMin) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); +typedef int (IMV_CALL * DLL_GetIntFeatureMax) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); +typedef int (IMV_CALL * DLL_GetIntFeatureInc) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); +typedef int (IMV_CALL * DLL_SetIntFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN int64_t intValue); +typedef int (IMV_CALL * DLL_GetDoubleFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); +typedef int (IMV_CALL * DLL_GetDoubleFeatureMin) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); +typedef int (IMV_CALL * DLL_GetDoubleFeatureMax) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); +typedef int (IMV_CALL * DLL_SetDoubleFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN double doubleValue); +typedef int (IMV_CALL * DLL_GetBoolFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT bool* pBoolValue); +typedef int (IMV_CALL * DLL_SetBoolFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN bool boolValue); +typedef int (IMV_CALL * DLL_GetEnumFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT uint64_t* pEnumValue); +typedef int (IMV_CALL * DLL_SetEnumFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN uint64_t enumValue); +typedef int (IMV_CALL * DLL_GetEnumFeatureSymbol) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT IMV_String* pEnumSymbol); +typedef int (IMV_CALL * DLL_SetEnumFeatureSymbol) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN const char* pEnumSymbol); +typedef int (IMV_CALL * DLL_GetEnumFeatureEntryNum) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT unsigned int* pEntryNum); +typedef int (IMV_CALL * DLL_GetEnumFeatureEntrys) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT IMV_EnumEntryList* pEnumEntryList); +typedef int (IMV_CALL * DLL_GetStringFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT IMV_String* pStringValue); +typedef int (IMV_CALL * DLL_SetStringFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN const char* pStringValue); +typedef int (IMV_CALL * DLL_ExecuteCommandFeature) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef int (IMV_CALL * DLL_PixelConvert) (IN IMV_HANDLE handle, IN_OUT IMV_PixelConvertParam* pstPixelConvertParam); +typedef int (IMV_CALL * DLL_OpenRecord) (IN IMV_HANDLE handle, IN IMV_RecordParam *pstRecordParam); +typedef int (IMV_CALL * DLL_InputOneFrame) (IN IMV_HANDLE handle, IN IMV_RecordFrameInfoParam *pstRecordFrameInfoParam); +typedef int (IMV_CALL * DLL_CloseRecord) (IN IMV_HANDLE handle); + + +int camera_init(); +int camera_start(int epx_time = 12 * 10000); +int camera_stop(); +int camera_cap(void** data, int& w, int& h, int time_out); + +} \ No newline at end of file diff --git a/camera_driver/CameraPublisher.cpp.bak b/camera_driver/CameraPublisher.cpp.bak new file mode 100644 index 0000000..0dc3d4c --- /dev/null +++ b/camera_driver/CameraPublisher.cpp.bak @@ -0,0 +1,798 @@ +#include +#include +#include +#include +#include +#include +#include "IMVApi.h" +#include "IMVDefines.h" + +#include +#include + +extern "C"{ + +#define MONO_CHANNEL_NUM 1 +#define RGB_CHANNEL_NUM 3 +#define BGR_CHANNEL_NUM 3 + +#define sleep(ms) usleep(1000 * ms) + +typedef const char* (IMV_CALL * DLL_GetVersion) (); +typedef int (IMV_CALL * DLL_EnumDevices) (OUT IMV_DeviceList *pDeviceList, IN unsigned int interfaceType); +typedef int (IMV_CALL * DLL_EnumDevicesByUnicast) (OUT IMV_DeviceList *pDeviceList, IN const char* pIpAddress); +typedef int (IMV_CALL * DLL_CreateHandle) (OUT IMV_HANDLE* handle, IN IMV_ECreateHandleMode mode, IN void* pIdentifier); +typedef int (IMV_CALL * DLL_DestroyHandle) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_GetDeviceInfo) (IN IMV_HANDLE handle, OUT IMV_DeviceInfo *pDevInfo); +typedef int (IMV_CALL * DLL_Open) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_OpenEx) (IN IMV_HANDLE handle, IN IMV_ECameraAccessPermission accessPermission); +typedef bool (IMV_CALL * DLL_IsOpen) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_Close) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_GIGE_ForceIpAddress) (IN IMV_HANDLE handle, IN const char* pIpAddress, IN const char* pSubnetMask, IN const char* pGateway); +typedef int (IMV_CALL * DLL_GIGE_GetAccessPermission) (IN IMV_HANDLE handle, IMV_ECameraAccessPermission* pAccessPermission); +typedef int (IMV_CALL * DLL_GIGE_SetAnswerTimeout) (IN IMV_HANDLE handle, IN unsigned int timeout); +typedef int (IMV_CALL * DLL_DownLoadGenICamXML) (IN IMV_HANDLE handle, IN const char* pFullFileName); +typedef int (IMV_CALL * DLL_SaveDeviceCfg) (IN IMV_HANDLE handle, IN const char* pFullFileName); +typedef int (IMV_CALL * DLL_LoadDeviceCfg) (IN IMV_HANDLE handle, IN const char* pFullFileName, OUT IMV_ErrorList* pErrorList); +typedef int (IMV_CALL * DLL_WriteUserPrivateData) (IN IMV_HANDLE handle, IN void* pBuffer, IN_OUT unsigned int* pLength); +typedef int (IMV_CALL * DLL_ReadUserPrivateData) (IN IMV_HANDLE handle, OUT void* pBuffer, IN_OUT unsigned int* pLength); +typedef int (IMV_CALL * DLL_WriteUARTData) (IN IMV_HANDLE handle, IN void* pBuffer, IN_OUT unsigned int* pLength); +typedef int (IMV_CALL * DLL_ReadUARTData) (IN IMV_HANDLE handle, OUT void* pBuffer, IN_OUT unsigned int* pLength); +typedef int (IMV_CALL * DLL_SubscribeConnectArg) (IN IMV_HANDLE handle, IN IMV_ConnectCallBack proc, IN void* pUser); +typedef int (IMV_CALL * DLL_SubscribeParamUpdateArg) (IN IMV_HANDLE handle, IN IMV_ParamUpdateCallBack proc, IN void* pUser); +typedef int (IMV_CALL * DLL_SubscribeStreamArg) (IN IMV_HANDLE handle, IN IMV_StreamCallBack proc, IN void* pUser); +typedef int (IMV_CALL * DLL_SubscribeMsgChannelArg) (IN IMV_HANDLE handle, IN IMV_MsgChannelCallBack proc, IN void* pUser); +typedef int (IMV_CALL * DLL_SetBufferCount) (IN IMV_HANDLE handle, IN unsigned int nSize); +typedef int (IMV_CALL * DLL_ClearFrameBuffer) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_GIGE_SetInterPacketTimeout) (IN IMV_HANDLE handle, IN unsigned int nTimeout); +typedef int (IMV_CALL * DLL_GIGE_SetSingleResendMaxPacketNum) (IN IMV_HANDLE handle, IN unsigned int maxPacketNum); +typedef int (IMV_CALL * DLL_GIGE_SetMaxLostPacketNum) (IN IMV_HANDLE handle, IN unsigned int maxLostPacketNum); +typedef int (IMV_CALL * DLL_StartGrabbing) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_StartGrabbingEx) (IN IMV_HANDLE handle, IN uint64_t maxImagesGrabbed, IN IMV_EGrabStrategy strategy); +typedef bool (IMV_CALL * DLL_IsGrabbing) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_StopGrabbing) (IN IMV_HANDLE handle); +typedef int (IMV_CALL * DLL_AttachGrabbing) (IN IMV_HANDLE handle, IN IMV_FrameCallBack proc, IN void* pUser); +typedef int (IMV_CALL * DLL_GetFrame) (IN IMV_HANDLE handle, OUT IMV_Frame* pFrame, IN unsigned int timeoutMS); +typedef int (IMV_CALL * DLL_ReleaseFrame) (IN IMV_HANDLE handle, IN IMV_Frame* pFrame); +typedef int (IMV_CALL * DLL_CloneFrame) (IN IMV_HANDLE handle, IN IMV_Frame* pFrame, OUT IMV_Frame* pCloneFrame); +typedef int (IMV_CALL * DLL_GetChunkDataByIndex) (IN IMV_HANDLE handle, IN IMV_Frame* pFrame, IN unsigned int index, OUT IMV_ChunkDataInfo *pChunkDataInfo); +typedef int (IMV_CALL * DLL_GetStatisticsInfo) (IN IMV_HANDLE handle, OUT IMV_StreamStatisticsInfo* pStreamStatsInfo); +typedef int (IMV_CALL * DLL_ResetStatisticsInfo) (IN IMV_HANDLE handle); +typedef bool (IMV_CALL * DLL_FeatureIsAvailable) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef bool (IMV_CALL * DLL_FeatureIsReadable) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef bool (IMV_CALL * DLL_FeatureIsWriteable) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef bool (IMV_CALL * DLL_FeatureIsStreamable) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef bool (IMV_CALL * DLL_FeatureIsValid) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef int (IMV_CALL * DLL_GetIntFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); +typedef int (IMV_CALL * DLL_GetIntFeatureMin) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); +typedef int (IMV_CALL * DLL_GetIntFeatureMax) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); +typedef int (IMV_CALL * DLL_GetIntFeatureInc) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); +typedef int (IMV_CALL * DLL_SetIntFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN int64_t intValue); +typedef int (IMV_CALL * DLL_GetDoubleFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); +typedef int (IMV_CALL * DLL_GetDoubleFeatureMin) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); +typedef int (IMV_CALL * DLL_GetDoubleFeatureMax) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); +typedef int (IMV_CALL * DLL_SetDoubleFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN double doubleValue); +typedef int (IMV_CALL * DLL_GetBoolFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT bool* pBoolValue); +typedef int (IMV_CALL * DLL_SetBoolFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN bool boolValue); +typedef int (IMV_CALL * DLL_GetEnumFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT uint64_t* pEnumValue); +typedef int (IMV_CALL * DLL_SetEnumFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN uint64_t enumValue); +typedef int (IMV_CALL * DLL_GetEnumFeatureSymbol) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT IMV_String* pEnumSymbol); +typedef int (IMV_CALL * DLL_SetEnumFeatureSymbol) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN const char* pEnumSymbol); +typedef int (IMV_CALL * DLL_GetEnumFeatureEntryNum) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT unsigned int* pEntryNum); +typedef int (IMV_CALL * DLL_GetEnumFeatureEntrys) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT IMV_EnumEntryList* pEnumEntryList); +typedef int (IMV_CALL * DLL_GetStringFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, OUT IMV_String* pStringValue); +typedef int (IMV_CALL * DLL_SetStringFeatureValue) (IN IMV_HANDLE handle, IN const char* pFeatureName, IN const char* pStringValue); +typedef int (IMV_CALL * DLL_ExecuteCommandFeature) (IN IMV_HANDLE handle, IN const char* pFeatureName); +typedef int (IMV_CALL * DLL_PixelConvert) (IN IMV_HANDLE handle, IN_OUT IMV_PixelConvertParam* pstPixelConvertParam); +typedef int (IMV_CALL * DLL_OpenRecord) (IN IMV_HANDLE handle, IN IMV_RecordParam *pstRecordParam); +typedef int (IMV_CALL * DLL_InputOneFrame) (IN IMV_HANDLE handle, IN IMV_RecordFrameInfoParam *pstRecordFrameInfoParam); +typedef int (IMV_CALL * DLL_CloseRecord) (IN IMV_HANDLE handle); + + + +// ***********开始: 这部分处理与SDK操作相机无关,用于显示设备列表 *********** +// ***********BEGIN: These functions are not related to API call and used to display device info*********** +// 数据帧回调函数 +// Data frame callback function +static void onGetFrame(IMV_Frame* pFrame, void* pUser) +{ + if (pFrame == NULL) + { + printf("pFrame is NULL\n"); + return; + } + + printf("Get frame blockId = %llu\n", pFrame->frameInfo.blockId); + + return; +} + +static void displayDeviceInfo(IMV_DeviceList deviceInfoList) +{ + IMV_DeviceInfo* pDevInfo = NULL; + unsigned int cameraIndex = 0; + char vendorNameCat[11]; + char cameraNameCat[16]; + + // 打印Title行 + // Print title line + printf("\nIdx Type Vendor Model S/N DeviceUserID IP Address \n"); + printf("------------------------------------------------------------------------------\n"); + + for (cameraIndex = 0; cameraIndex < deviceInfoList.nDevNum; cameraIndex++) + { + pDevInfo = &deviceInfoList.pDevInfo[cameraIndex]; + // 设备列表的相机索引 最大表示字数:3 + // Camera index in device list, display in 3 characters + printf("%-3d", cameraIndex + 1); + + // 相机的设备类型(GigE,U3V,CL,PCIe) + // Camera type + switch (pDevInfo->nCameraType) + { + case typeGigeCamera:printf(" GigE");break; + case typeU3vCamera:printf(" U3V ");break; + case typeCLCamera:printf(" CL ");break; + case typePCIeCamera:printf(" PCIe");break; + default:printf(" ");break; + } + + // 制造商信息 最大表示字数:10 + // Camera vendor name, display in 10 characters + if (strlen(pDevInfo->vendorName) > 10) + { + memcpy(vendorNameCat, pDevInfo->vendorName, 7); + vendorNameCat[7] = '\0'; + strcat(vendorNameCat, "..."); + printf(" %-10.10s", vendorNameCat); + } + else + { + printf(" %-10.10s", pDevInfo->vendorName); + } + + // 相机的型号信息 最大表示字数:10 + // Camera model name, display in 10 characters + printf(" %-10.10s", pDevInfo->modelName); + + // 相机的序列号 最大表示字数:15 + // Camera serial number, display in 15 characters + printf(" %-15.15s", pDevInfo->serialNumber); + + // 自定义用户ID 最大表示字数:15 + // Camera user id, display in 15 characters + if (strlen(pDevInfo->cameraName) > 15) + { + memcpy(cameraNameCat, pDevInfo->cameraName, 12); + cameraNameCat[12] = '\0'; + strcat(cameraNameCat, "..."); + printf(" %-15.15s", cameraNameCat); + } + else + { + printf(" %-15.15s", pDevInfo->cameraName); + } + + // GigE相机时获取IP地址 + // IP address of GigE camera + if (pDevInfo->nCameraType == typeGigeCamera) + { + printf(" %s", pDevInfo->DeviceSpecificInfo.gigeDeviceInfo.ipAddress); + } + + printf("\n"); + } + + return; +} + +static char* trim(char* pStr) +{ + char* pDst = pStr; + char* pTemStr = NULL; + + if (pDst != NULL) + { + pTemStr = pDst + strlen(pStr) - 1; + while (*pDst == ' ') + { + pDst++; + } + while ((pTemStr > pDst) && (*pTemStr == ' ')) + { + *pTemStr-- = '\0'; + } + } + return pDst; +} + +static int isInputValid(char* pInpuStr) +{ + char numChar; + char* pStr = pInpuStr; + while (*pStr != '\0') + { + numChar = *pStr; + if ((numChar > '9') || (numChar < '0')) + { + return -1; + } + pStr++; + } + return 0; +} + +static unsigned int selectDevice(unsigned int cameraCnt) +{ + char inputStr[256]; + char* pTrimStr; + int inputIndex = -1; + int ret = -1; + char* find = NULL; + + printf("\nPlease input the camera index: "); + while (1) + { + memset(inputStr, 0, sizeof(inputStr)); + fgets(inputStr, sizeof(inputStr), stdin); + + // 清空输入缓存 + // clear flush + fflush(stdin); + + // fgets比gets多吃一个换行符号,取出换行符号 + // fgets eats one more line feed symbol than gets, and takes out the line feed symbol + find = strchr(inputStr, '\n'); + if (find) { *find = '\0'; } + + pTrimStr = trim(inputStr); + ret = isInputValid(pTrimStr); + if (ret == 0) + { + inputIndex = atoi(pTrimStr); + // 输入的序号从1开始 + // Input index starts from 1 + inputIndex -= 1; + if ((inputIndex >= 0) && (inputIndex < (int)cameraCnt)) + { + break; + } + } + + printf("Input invalid! Please input the camera index: "); + } + return (unsigned int)inputIndex; +} + +// ***********结束: 这部分处理与SDK操作相机无关,用于显示设备列表 *********** +// ***********END: These functions are not related to API call and used to display device info*********** +static int setSoftTriggerConf(void* libHandle, IMV_HANDLE devHandle) +{ + int ret = IMV_OK; + // 获取设置触发源为软触发函数地址 + DLL_SetEnumFeatureSymbol DLLSetEnumFeatureSymbol = (DLL_SetEnumFeatureSymbol)dlsym(libHandle, "IMV_SetEnumFeatureSymbol"); + if (NULL == DLLSetEnumFeatureSymbol) + { + printf("Get IMV_SetEnumFeatureSymbol address failed!\n"); + return ret; + } + + // 设置触发源为软触发 + // Set trigger source to Software + ret = DLLSetEnumFeatureSymbol(devHandle, "TriggerSource", "Software"); + if (IMV_OK != ret) + { + printf("Set triggerSource value failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 设置触发器 + // Set trigger selector to FrameStart + ret = DLLSetEnumFeatureSymbol(devHandle, "TriggerSelector", "FrameStart"); + if (IMV_OK != ret) + { + printf("Set triggerSelector value failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 设置触发模式 + // Set trigger mode to On + ret = DLLSetEnumFeatureSymbol(devHandle, "TriggerMode", "On"); + if (IMV_OK != ret) + { + printf("Set triggerMode value failed! ErrorCode[%d]\n", ret); + return ret; + } + + return ret; +} + +// Image convert +static int imageConvert(void* libHandle, IMV_HANDLE devHandle, IMV_Frame frame, IMV_EPixelType convertFormat) +{ + IMV_PixelConvertParam stPixelConvertParam; + unsigned char* pDstBuf = NULL; + unsigned int nDstBufSize = 0; + int ret = IMV_OK; + FILE* hFile = NULL; + const char* pFileName = NULL; + const char* pConvertFormatStr = NULL; + + // 获取设置触发源为软触发函数地址 + DLL_PixelConvert DLLPixelConvert = (DLL_PixelConvert)dlsym(libHandle, "IMV_PixelConvert"); + if (NULL == DLLPixelConvert) + { + printf("Get IMV_PixelConvert address failed!\n"); + return ret; + } + + switch (convertFormat) + { + case gvspPixelRGB8: + nDstBufSize = sizeof(unsigned char) * frame.frameInfo.width * frame.frameInfo.height * 3; + pFileName = (const char*)"convertRGB8.bmp"; + pConvertFormatStr = (const char*)"RGB8"; + break; + + case gvspPixelBGR8: + nDstBufSize = sizeof(unsigned char) * frame.frameInfo.width * frame.frameInfo.height * 3; + pFileName = (const char*)"convertBGR8.bmp"; + pConvertFormatStr = (const char*)"BGR8"; + break; + case gvspPixelBGRA8: + nDstBufSize = sizeof(unsigned char) * frame.frameInfo.width * frame.frameInfo.height * 4; + pFileName = (const char*)"convertBGRA8.bmp"; + pConvertFormatStr = (const char*)"BGRA8"; + break; + case gvspPixelMono8: + default: + nDstBufSize = sizeof(unsigned char) * frame.frameInfo.width * frame.frameInfo.height; + pFileName = (const char*)"convertMono8.bmp"; + pConvertFormatStr = (const char*)"Mono8"; + break; + } + + pDstBuf = (unsigned char*)malloc(nDstBufSize); + if (NULL == pDstBuf) + { + printf("malloc pDstBuf failed!\n"); + return -1; + } + + // 图像转换成BGR8 + // convert image to BGR8 + memset(&stPixelConvertParam, 0, sizeof(stPixelConvertParam)); + stPixelConvertParam.nWidth = frame.frameInfo.width; + stPixelConvertParam.nHeight = frame.frameInfo.height; + stPixelConvertParam.ePixelFormat = frame.frameInfo.pixelFormat; + stPixelConvertParam.pSrcData = frame.pData; + stPixelConvertParam.nSrcDataLen = frame.frameInfo.size; + stPixelConvertParam.nPaddingX = frame.frameInfo.paddingX; + stPixelConvertParam.nPaddingY = frame.frameInfo.paddingY; + stPixelConvertParam.eBayerDemosaic = demosaicNearestNeighbor; + stPixelConvertParam.eDstPixelFormat = convertFormat; + stPixelConvertParam.pDstBuf = pDstBuf; + stPixelConvertParam.nDstBufSize = nDstBufSize; + + + ret = DLLPixelConvert(devHandle, &stPixelConvertParam); + if (IMV_OK == ret) + { + printf("image convert to %s successfully! nDstDataLen (%u)\n", + pConvertFormatStr, stPixelConvertParam.nDstBufSize); + + cv::Mat im(stPixelConvertParam.nHeight, stPixelConvertParam.nWidth, CV_8UC3, stPixelConvertParam.pDstBuf); + + // // for test + // // 内参矩阵 + // cv::Mat cameraMatrix = (cv::Mat_(3, 3) << 11057.154, 0, 4538.85, 0, 11044.943, 3350.918, 0, 0, 1); + // // 设置畸变系数 + // cv::Mat distCoeffs = (cv::Mat_(1, 5) << 0.311583980, -14.5864013, -0.00630134677, -0.00466401902, 183.662957); + // // 准备输出图像 + // cv::Mat undistortedImg; + // // 使用cv::undistort函数进行校正 + // cv::undistort(im, undistortedImg, cameraMatrix, distCoeffs); + + + cv::imwrite("/home/caowei/catkin_ws/output.png", im); + cv::imwrite("output.png", im); + + // hFile = fopen(pFileName, "wb"); + // if (hFile != NULL) + // { + // fwrite((void*)pDstBuf, 1, stPixelConvertParam.nDstBufSize, hFile); + // fclose(hFile); + // } + // else + // { + // // 如果打开失败,请用root权限执行 + // // If opefailed, Run as root + // printf("Open file (%s) failed!\n", pFileName); + // } + } + else + { + printf("image convert to %s failed! ErrorCode[%d]\n", pConvertFormatStr, ret); + } + + if (pDstBuf) + { + free(pDstBuf); + pDstBuf = NULL; + } + + return IMV_OK; +} + +static void sendToRos(IMV_Frame frame) +{ + IMV_FlipImageParam stFlipImageParam; + unsigned int nChannelNum = 0; + int ret = IMV_OK; + FILE* hFile = NULL; + + memset(&stFlipImageParam, 0, sizeof(stFlipImageParam)); + + if (gvspPixelBGR8 == frame.frameInfo.pixelFormat) + { + stFlipImageParam.pSrcData = frame.pData; + stFlipImageParam.nSrcDataLen = frame.frameInfo.width * frame.frameInfo.height * BGR_CHANNEL_NUM; + stFlipImageParam.ePixelFormat = frame.frameInfo.pixelFormat; + nChannelNum = BGR_CHANNEL_NUM; + } + else + { + printf("image convert to BGR8 failed! ErrorCode[%d]\n", ret); + } + + // 向ros发送/image消息 + do + { + + } while (false); + +} + + +int main() +{ + int ret = IMV_OK; + unsigned int cameraIndex = 0; + IMV_HANDLE devHandle = NULL; + void* libHandle = NULL; + DLL_DestroyHandle DLLDestroyHandle = NULL; + IMV_Frame frame; + + // 加载SDK库 + // Load SDK library + libHandle = dlopen("libMVSDK.so", RTLD_LAZY); + if (NULL == libHandle) + { + printf("Load MVSDKmd.dll library failed!\n"); + return 0; + } + + // 获取发现设备接口函数地址 + // Get discover camera interface address + DLL_EnumDevices DLLEnumDevices = (DLL_EnumDevices)dlsym(libHandle, "IMV_EnumDevices"); + if (NULL == DLLEnumDevices) + { + printf("Get IMV_EnumDevices address failed!\n"); + return 0; + } + + // 获取创建设备句柄接口函数地址 + // Get create Device Handle interface address + DLL_CreateHandle DLLCreateHandle = (DLL_CreateHandle)dlsym(libHandle, "IMV_CreateHandle"); + if (NULL == DLLCreateHandle) + { + printf("Get IMV_CreateHandle address failed!\n"); + return 0; + } + + // 获取销毁设备句柄接口函数地址 + // Get destroy Device Handle interface address + DLLDestroyHandle = (DLL_DestroyHandle)dlsym(libHandle, "IMV_DestroyHandle"); + if (NULL == DLLDestroyHandle) + { + printf("Get IMV_DestroyHandle address failed!\n"); + return 0; + } + + // 获取打开相机接口函数地址 + // Get open camera interface address + DLL_Open DLLOpen = (DLL_Open)dlsym(libHandle, "IMV_Open"); + if (NULL == DLLOpen) + { + printf("Get IMV_Open address failed!\n"); + return 0; + } + + // 获取注册数据帧回调接口函数地址 + // Get register data frame callback interface address + DLL_AttachGrabbing DLLAttachGrabbing = (DLL_AttachGrabbing)dlsym(libHandle, "IMV_AttachGrabbing"); + if (NULL == DLLAttachGrabbing) + { + printf("Get IMV_AttachGrabbing address failed!\n"); + return 0; + } + + // 获取开始拉流接口函数地址 + // Get start grabbing interface address + DLL_StartGrabbing DLLStartGrabbing = (DLL_StartGrabbing)dlsym(libHandle, "IMV_StartGrabbing"); + if (NULL == DLLStartGrabbing) + { + printf("Get IMV_StartGrabbing address failed!\n"); + return 0; + } + + // 获取停止拉流接口函数地址 + // Get stop grabbing interface address + DLL_StopGrabbing DLLStopGrabbing = (DLL_StopGrabbing)dlsym(libHandle, "IMV_StopGrabbing"); + if (NULL == DLLStopGrabbing) + { + printf("Get IMV_StopGrabbing address failed!\n"); + return 0; + } + + // 获取 + + // 获取关闭相机接口函数地址 + // Get close camera interface address + DLL_Close DLLClose = (DLL_Close)dlsym(libHandle, "IMV_Close"); + if (NULL == DLLClose) + { + printf("Get IMV_Close address failed!\n"); + return 0; + } + + // 获取获取一帧图像函数地址 + DLL_GetFrame DLLGetFrame = (DLL_GetFrame)dlsym(libHandle, "IMV_GetFrame"); + if (NULL == DLLGetFrame) + { + printf("Get IMV_GetFrame address failed!\n"); + return 0; + } + + DLL_ReleaseFrame DLLReleaseFrame = (DLL_ReleaseFrame)dlsym(libHandle, "IMV_ReleaseFrame"); + if (NULL == DLLReleaseFrame) + { + printf("Get IMV_ReleaseFrame address failed!\n"); + return 0; + } + + DLL_ClearFrameBuffer DLLClearFrameBuffer = (DLL_ClearFrameBuffer)dlsym(libHandle, "IMV_ClearFrameBuffer"); + if (NULL == DLLClearFrameBuffer) + { + printf("Get IMV_ClearFrameBuffer address failed!\n"); + return 0; + } + + DLL_ExecuteCommandFeature DLLExecuteCommandFeature = (DLL_ExecuteCommandFeature)dlsym(libHandle, "IMV_ExecuteCommandFeature"); + if (NULL == DLLExecuteCommandFeature) + { + printf("Get IMV_ExecuteCommandFeature address failed!\n"); + return 0; + } + + DLL_SetIntFeatureValue DLLSetIntFeatureValue = (DLL_SetIntFeatureValue)dlsym(libHandle, "IMV_SetIntFeatureValue"); + if (NULL == DLLSetIntFeatureValue) + { + printf("Get IMV_SetIntFeatureValue address failed!\n"); + return 0; + } + + DLL_SetDoubleFeatureValue DLLSetDoubleFeatureValue = (DLL_SetDoubleFeatureValue)dlsym(libHandle, "IMV_SetDoubleFeatureValue"); + if (NULL == DLLSetDoubleFeatureValue) + { + printf("Get IMV_SetDoubleFeatureValue address failed!\n"); + return 0; + } + + + +////////////////////// 检查接口结束 + // 发现设备 + // discover camera + IMV_DeviceList deviceInfoList; + ret = DLLEnumDevices(&deviceInfoList, interfaceTypeAll); + if (IMV_OK != ret) + { + printf("Enumeration devices failed! ErrorCode[%d]\n", ret); + return 0; + } + + if (deviceInfoList.nDevNum < 1) + { + printf("no camera\n"); + return 0; + } + + // 打印相机基本信息(序号,类型,制造商信息,型号,序列号,用户自定义ID,IP地址) + // Print camera info (Index, Type, Vendor, Model, Serial number, DeviceUserID, IP Address) + + displayDeviceInfo(deviceInfoList); + // 选择需要连接的相机 + // Select one camera to connect to + // cameraIndex = selectDevice(deviceInfoList.nDevNum); + cameraIndex = 0; // 第一个相机 + + // 创建设备句柄 + // Create Device Handle + ret = DLLCreateHandle(&devHandle, modeByIndex, (void*)&cameraIndex); + if (IMV_OK != ret) + { + printf("Create devHandle failed! ErrorCode[%d]\n", ret); + return 0; + } + + // 打开相机 + ret = DLLOpen(devHandle); + if (IMV_OK != ret) + { + printf("Open camera failed! ErrorCode[%d]\n", ret); + return 0; + } + + // 设置软触发模式 + ret = setSoftTriggerConf(libHandle, devHandle); + if (IMV_OK != ret) + { + printf("setSoftTriggerConf failed! ErrorCode[%d]\n", ret); + return 0; + } + + ret = DLLSetIntFeatureValue(devHandle, "Width", 9344); + if (IMV_OK != ret) + { + printf("Set feature value Width failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLSetIntFeatureValue(devHandle, "Height", 7000); + if (IMV_OK != ret) + { + printf("Set feature value Height failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLSetIntFeatureValue(devHandle, "OffsetX", 0); + if (IMV_OK != ret) + { + printf("Set feature value OffsetX failed! ErrorCode[%d]\n", ret); + return ret; + } + + ret = DLLSetIntFeatureValue(devHandle, "OffsetY", 0); + if (IMV_OK != ret) + { + printf("Set feature value OffsetY failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 设置属性值曝光 + // Set feature value + ret = DLLSetDoubleFeatureValue(devHandle, "ExposureTime", 12*10000); + if (IMV_OK != ret) + { + printf("Set feature value failed! ErrorCode[%d]\n", ret); + return ret; + } + + // // 非多线程,不需要注册回调 + // // 注册数据帧回调函数 + // // Register data frame callback function + // ret = DLLAttachGrabbing(devHandle, onGetFrame, NULL); + // if (IMV_OK != ret) + // { + // printf("Attach grabbing failed! ErrorCode[%d]\n", ret); + // return 0; + // } + + // 开始拉流 + // Start grabbing + ret = DLLStartGrabbing(devHandle); + if (IMV_OK != ret) + { + printf("Start grabbing failed! ErrorCode[%d]\n", ret); + return 0; + } + + /////////////////////////获取一帧图像//////////////////////////// + + // 清除帧数据缓存 + // Clear frame buffer + ret = DLLClearFrameBuffer(devHandle); + if (IMV_OK != ret) + { + printf("Clear frame buffer failed! ErrorCode[%d]\n", ret); + return ret; + } + + // 执行软触发 + // Execute soft trigger + ret = DLLExecuteCommandFeature(devHandle, "TriggerSoftware"); + if (IMV_OK != ret) + { + printf("Execute TriggerSoftware failed! ErrorCode[%d]\n", ret); + return ret; + } + +sleep(2000); + // 获取一帧图像, TIMEOUT 5000ms + ret = DLLGetFrame(devHandle, &frame, 5000); + if (IMV_OK != ret) + { + printf("Get frame failed! ErrorCode[%d]\n", ret); + return 0; + } + + printf("width %d\n", frame.frameInfo.width); + printf("Height %d\n", frame.frameInfo.height); + + ret = imageConvert(libHandle, devHandle, frame, gvspPixelBGR8); + if (IMV_OK != ret) + { + printf("imageConvert failed! ErrorCode[%d]\n", ret); + return 0; + } + // printf("11111111111111\n", ret); + // cv::Mat im(frame.frameInfo.width, frame.frameInfo.height, CV_8UC3, frame.pData); + // cv::imwrite("/home/caowei/catkin_ws/output.png", im); + // cv::imwrite("output.png", im); + // printf("22222222222222\n", ret); + // // 向ros送 /image消息 + // sendToRos(frame); + + // 释放图像缓存 + ret = DLLReleaseFrame(devHandle, &frame); + if (IMV_OK != ret) + { + printf("Release frame failed! ErrorCode[%d]\n", ret); + return 0; + } + //////////////////////////////////////////////////////////////// + + // // 取图2秒 + // // get frame 2 seconds + // sleep(2000); + + // 停止拉流 + // Stop grabbing + ret = DLLStopGrabbing(devHandle); + if (IMV_OK != ret) + { + printf("Stop grabbing failed! ErrorCode[%d]\n", ret); + return 0; + } + + // 关闭相机 + // Close camera + ret = DLLClose(devHandle); + if (IMV_OK != ret) + { + printf("Close camera failed! ErrorCode[%d]\n", ret); + return 0; + } + + // 销毁设备句柄 + // Destroy Device Handle + if (NULL != devHandle) + { + // 销毁设备句柄 + // Destroy Device Handle + DLLDestroyHandle(devHandle); + } + + if (NULL != libHandle) + { + dlclose(libHandle); + } + + printf("end...\n"); + // getchar(); + + return 0; +} + +} \ No newline at end of file diff --git a/camera_driver/IMVApi.h b/camera_driver/IMVApi.h new file mode 100644 index 0000000..af056da --- /dev/null +++ b/camera_driver/IMVApi.h @@ -0,0 +1,1071 @@ +/// \mainpage +/// \~chinese +/// \htmlinclude mainpage_chs.html +/// \~english +/// \htmlinclude mainpage_eng.html + +#ifndef __IMV_API_H__ +#define __IMV_API_H__ + +#include "IMVDefines.h" + +/// \~chinese +/// \brief 动态库导入导出定义 +/// \~english +/// \brief Dynamic library import and export definition +#if (defined (_WIN32) || defined(WIN64)) + #ifdef IMV_API_DLL_BUILD + #define IMV_API _declspec(dllexport) + #else + #define IMV_API _declspec(dllimport) + #endif + + #define IMV_CALL __stdcall +#else + #define IMV_API + #define IMV_CALL +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +/// \~chinese +/// \brief 获取版本信息 +/// \return 成功时返回版本信息,失败时返回NULL +/// \~english +/// \brief get version information +/// \return Success, return version info. Failure, return NULL +IMV_API const char* IMV_CALL IMV_GetVersion(void); + +/// \~chinese +/// \brief 枚举设备 +/// \param pDeviceList [OUT] 设备列表 +/// \param interfaceType [IN] 待枚举的接口类型, 类型可任意组合,如 interfaceTypeGige | interfaceTypeUsb3 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 1、当interfaceType = interfaceTypeAll 时,枚举所有接口下的在线设备\n +/// 2、当interfaceType = interfaceTypeGige 时,枚举所有GigE网口下的在线设备\n +/// 3、当interfaceType = interfaceTypeUsb3 时,枚举所有USB接口下的在线设备\n +/// 4、当interfaceType = interfaceTypeCL 时,枚举所有CameraLink接口下的在线设备\n +/// 5、该接口下的interfaceType支持任意接口类型的组合,如,若枚举所有GigE网口和USB3接口下的在线设备时, +/// 可将interfaceType设置为 interfaceType = interfaceTypeGige | interfaceTypeUsb3,其它接口类型组合以此类推 +/// \~english +/// \brief Enumerate Device +/// \param pDeviceList [OUT] Device list +/// \param interfaceType [IN] The interface type you want to find, support any interface type combination, sucn as interfaceTypeGige | interfaceTypeUsb3 +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// 1、when interfaceType = interfaceTypeAll, enumerate devices in all interface types\n +/// 2、when interfaceType = interfaceTypeGige, enumerate devices in GigE interface \n +/// 3、when interfaceType = interfaceTypeUsb3, enumerate devices in USB interface\n +/// 4、when interfaceType = interfaceTypeCL, enumerate devices in CameraLink interface\n +/// 5、interfaceType supports any interface type combination. For example, if you want to find all GigE and USB3 devices, +/// you can set interfaceType as interfaceType = interfaceTypeGige | interfaceTypeUsb3. +IMV_API int IMV_CALL IMV_EnumDevices(OUT IMV_DeviceList *pDeviceList, IN unsigned int interfaceType); + +/// \~chinese +/// \brief 以单播形式枚举设备, 仅限Gige设备使用 +/// \param pDeviceList [OUT] 设备列表 +/// \param pIpAddress [IN] 设备的IP地址 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Enumerate device by unicast mode. Only for Gige device. +/// \param pDeviceList [OUT] Device list +/// \param pIpAddress [IN] IP address of the device +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_EnumDevicesByUnicast(OUT IMV_DeviceList *pDeviceList, IN const char* pIpAddress); + +/// \~chinese +/// \brief 通过指定标示符创建设备句柄,如指定索引、设备键、设备自定义名、IP地址 +/// \param handle [OUT] 设备句柄 +/// \param mode [IN] 创建设备方式 +/// \param pIdentifier [IN] 指定标示符(设备键、设备自定义名、IP地址为char类型指针强转void类型指针,索引为unsigned int类型指针强转void类型指针) +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Create device handle by specifying identifiers, such as specifying index, device key, device userID, and IP address +/// \param handle [OUT] Device handle +/// \param mode [IN] Create handle mode +/// \param pIdentifier [IN] Specifying identifiers(device key, device userID, and IP address is char* forced to void*, index is unsigned int* forced to void*) +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_CreateHandle(OUT IMV_HANDLE* handle, IN IMV_ECreateHandleMode mode, IN void* pIdentifier); + +/// \~chinese +/// \brief 销毁设备句柄 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Destroy device handle +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_DestroyHandle(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 获取设备信息 +/// \param handle [IN] 设备句柄 +/// \param pDevInfo [OUT] 设备信息 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get device information +/// \param handle [IN] Device handle +/// \param pDevInfo [OUT] Device information +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetDeviceInfo(IN IMV_HANDLE handle, OUT IMV_DeviceInfo *pDevInfo); + +/// \~chinese +/// \brief 打开设备 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Open Device +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_Open(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 打开设备 +/// \param handle [IN] 设备句柄 +/// \param accessPermission [IN] 控制通道权限(IMV_Open默认使用accessPermissionControl权限) +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Open Device +/// \param handle [IN] Device handle +/// \param accessPermission [IN] Control access permission(Default used accessPermissionControl in IMV_Open) +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_OpenEx(IN IMV_HANDLE handle, IN IMV_ECameraAccessPermission accessPermission); + +/// \~chinese +/// \brief 判断设备是否已打开 +/// \param handle [IN] 设备句柄 +/// \return 打开状态,返回true;关闭状态或者掉线状态,返回false +/// \~english +/// \brief Check whether device is opened or not +/// \param handle [IN] Device handle +/// \return Opened, return true. Closed or Offline, return false +IMV_API bool IMV_CALL IMV_IsOpen(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 关闭设备 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Close Device +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_Close(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 修改设备IP, 仅限Gige设备使用 +/// \param handle [IN] 设备句柄 +/// \param pIpAddress [IN] IP地址 +/// \param pSubnetMask [IN] 子网掩码 +/// \param pGateway [IN] 默认网关 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 1、调用该函数时如果pSubnetMask和pGateway都设置了有效值,则以此有效值为准;\n +/// 2、调用该函数时如果pSubnetMask和pGateway都设置了NULL,则内部实现时用它所连接网卡的子网掩码和网关代替\n +/// 3、调用该函数时如果pSubnetMask和pGateway两者中其中一个为NULL,另一个非NULL,则返回错误 +/// \~english +/// \brief Modify device IP. Only for Gige device. +/// \param handle [IN] Device handle +/// \param pIpAddress [IN] IP address +/// \param pSubnetMask [IN] SubnetMask +/// \param pGateway [IN] Gateway +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// 1、When callback this function, if the values of pSubnetMask and pGateway are both valid then we consider the value is correct\n +/// 2、When callback this function, if the values of pSubnetMask and pGateway are both NULL, +/// then these values will be replaced by the subnetmask and gateway of NIC which this device connect to.\n +/// 3、When callback this function, if there is one value of pSubnetMask or pGateway is NULL and the other one is not NULL, then return error +IMV_API int IMV_CALL IMV_GIGE_ForceIpAddress(IN IMV_HANDLE handle, IN const char* pIpAddress, IN const char* pSubnetMask, IN const char* pGateway); + +/// \~chinese +/// \brief 获取设备的当前访问权限, 仅限Gige设备使用 +/// \param handle [IN] 设备句柄 +/// \param pAccessPermission [OUT] 设备的当前访问权限 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get current access permission of device. Only for Gige device. +/// \param handle [IN] Device handle +/// \param pAccessPermission [OUT] Current access permission of device +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GIGE_GetAccessPermission(IN IMV_HANDLE handle, OUT IMV_ECameraAccessPermission* pAccessPermission); + +/// \~chinese +/// \brief 设置设备对sdk命令的响应超时时间,仅限Gige设备使用 +/// \param handle [IN] 设备句柄 +/// \param timeout [IN] 超时时间,单位ms +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set the response timeout interval of device sends command to the API. Only for Gige device. +/// \param handle [IN] Device handle +/// \param timeout [IN] time out, unit:ms +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GIGE_SetAnswerTimeout(IN IMV_HANDLE handle, IN unsigned int timeout); + +/// \~chinese +/// \brief 下载设备描述XML文件,并保存到指定路径,如:D:\\xml.zip +/// \param handle [IN] 设备句柄 +/// \param pFullFileName [IN] 文件要保存的路径 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Download device description XML file, and save the files to specified path. e.g. D:\\xml.zip +/// \param handle [IN] Device handle +/// \param pFullFileName [IN] The full paths where the downloaded XMl files would be saved to +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_DownLoadGenICamXML(IN IMV_HANDLE handle, IN const char* pFullFileName); + +/// \~chinese +/// \brief 保存设备配置到指定的位置。同名文件已存在时,覆盖。 +/// \param handle [IN] 设备句柄 +/// \param pFullFileName [IN] 导出的设备配置文件全名(含路径),如:D:\\config.xml 或 D:\\config.mvcfg +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Save the configuration of the device. Overwrite the file if exists. +/// \param handle [IN] Device handle +/// \param pFullFileName [IN] The full path name of the property file(xml). e.g. D:\\config.xml or D:\\config.mvcfg +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SaveDeviceCfg(IN IMV_HANDLE handle, IN const char* pFullFileName); + +/// \~chinese +/// \brief 从文件加载设备xml配置 +/// \param handle [IN] 设备句柄 +/// \param pFullFileName [IN] 设备配置(xml)文件全名(含路径),如:D:\\config.xml 或 D:\\config.mvcfg +/// \param pErrorList [OUT] 加载失败的属性名列表。存放加载失败的属性上限为IMV_MAX_ERROR_LIST_NUM。 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief load the configuration of the device +/// \param handle [IN] Device handle +/// \param pFullFileName [IN] The full path name of the property file(xml). e.g. D:\\config.xml or D:\\config.mvcfg +/// \param pErrorList [OUT] The list of load failed properties. The failed to load properties list up to IMV_MAX_ERROR_LIST_NUM. +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_LoadDeviceCfg(IN IMV_HANDLE handle, IN const char* pFullFileName, OUT IMV_ErrorList* pErrorList); + +/// \~chinese +/// \brief 写用户自定义数据。相机内部保留32768字节用于用户存储自定义数据(此功能针对本品牌相机,其它品牌相机无此功能) +/// \param handle [IN] 设备句柄 +/// \param pBuffer [IN] 数据缓冲的指针 +/// \param pLength [IN] 期望写入的字节数 [OUT] 实际写入的字节数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Write user-defined data; Inside the camera, there are 32768 bytes reserved for user to store private data (Only for our own camera has this function) +/// \param handle [IN] Device handle +/// \param pBuffer [IN] Pointer of the data buffer +/// \param pLength [IN] Byte count written expected [OUT] Byte count written in fact +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_WriteUserPrivateData(IN IMV_HANDLE handle, IN void* pBuffer, IN_OUT unsigned int* pLength); + +/// \~chinese +/// \brief 读用户自定义数据。相机内部保留32768字节用于用户存储自定义数据(此功能针对本品牌相机,其它品牌相机无此功能) +/// \param handle [IN] 设备句柄 +/// \param pBuffer [OUT] 数据缓冲的指针 +/// \param pLength [IN] 期望读出的字节数 [OUT] 实际读出的字节数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Read user-defined data; Inside the camera, there are 32768 bytes reserved for user to store private data (Only for our own camera has this function) +/// \param handle [IN] Device handle +/// \param pBuffer [OUT] Pointer of the data buffer +/// \param pLength [IN] Byte count read expected [OUT] Byte count read in fact +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ReadUserPrivateData(IN IMV_HANDLE handle, OUT void* pBuffer, IN_OUT unsigned int* pLength); + +/// \~chinese +/// \brief 往相机串口寄存器写数据,每次写会清除掉上次的数据(此功能只支持包含串口功能的本品牌相机) +/// \param handle [IN] 设备句柄 +/// \param pBuffer [IN] 数据缓冲的指针 +/// \param pLength [IN] 期望写入的字节数 [OUT] 实际写入的字节数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Write serial data to camera serial register, will erase the data writen before (Only for our own camera with serial port has this function) +/// \param handle [IN] Device handle +/// \param pBuffer [IN] Pointer of the data buffer +/// \param pLength [IN] Byte count written expected [OUT] Byte count written in fact +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_WriteUARTData(IN IMV_HANDLE handle, IN void* pBuffer, IN_OUT unsigned int* pLength); + +/// \~chinese +/// \brief 从相机串口寄存器读取串口数据(此功能只支持包含串口功能的本品牌相机 ) +/// \param handle [IN] 设备句柄 +/// \param pBuffer [OUT] 数据缓冲的指针 +/// \param pLength [IN] 期望读出的字节数 [OUT] 实际读出的字节数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Read serial data from camera serial register (Only for our own camera with serial port has this function) +/// \param handle [IN] Device handle +/// \param pBuffer [OUT] Pointer of the data buffer +/// \param pLength [IN] Byte count read expected [OUT] Byte count read in fact +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ReadUARTData(IN IMV_HANDLE handle, OUT void* pBuffer, IN_OUT unsigned int* pLength); + +/// \~chinese +/// \brief 设备连接状态事件回调注册 +/// \param handle [IN] 设备句柄 +/// \param proc [IN] 设备连接状态事件回调函数 +/// \param pUser [IN] 用户自定义数据, 可设为NULL +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持一个回调函数,且设备关闭后,注册会失效,打开设备后需重新注册 +/// \~english +/// \brief Register call back function of device connection status event. +/// \param handle [IN] Device handle +/// \param proc [IN] Call back function of device connection status event +/// \param pUser [IN] User defined data,It can be set to NULL +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only one call back function is supported.\n +/// Registration becomes invalid after the device is closed, , and need to re-register after the device is opened +IMV_API int IMV_CALL IMV_SubscribeConnectArg(IN IMV_HANDLE handle, IN IMV_ConnectCallBack proc, IN void* pUser); + +/// \~chinese +/// \brief 参数更新事件回调注册 +/// \param handle [IN] 设备句柄 +/// \param proc [IN] 参数更新注册的事件回调函数 +/// \param pUser [IN] 用户自定义数据, 可设为NULL +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持一个回调函数,且设备关闭后,注册会失效,打开设备后需重新注册 +/// \~english +/// \brief Register call back function of parameter update event. +/// \param handle [IN] Device handle +/// \param proc [IN] Call back function of parameter update event +/// \param pUser [IN] User defined data,It can be set to NULL +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only one call back function is supported.\n +/// Registration becomes invalid after the device is closed, , and need to re-register after the device is opened +IMV_API int IMV_CALL IMV_SubscribeParamUpdateArg(IN IMV_HANDLE handle, IN IMV_ParamUpdateCallBack proc, IN void* pUser); + +/// \~chinese +/// \brief 流通道事件回调注册 +/// \param handle [IN] 设备句柄 +/// \param proc [IN] 流通道事件回调注册函数 +/// \param pUser [IN] 用户自定义数据, 可设为NULL +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持一个回调函数,且设备关闭后,注册会失效,打开设备后需重新注册 +/// \~english +/// \brief Register call back function of stream channel event. +/// \param handle [IN] Device handle +/// \param proc [IN] Call back function of stream channel event +/// \param pUser [IN] User defined data,It can be set to NULL +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only one call back function is supported.\n +/// Registration becomes invalid after the device is closed, , and need to re-register after the device is opened +IMV_API int IMV_CALL IMV_SubscribeStreamArg(IN IMV_HANDLE handle, IN IMV_StreamCallBack proc, IN void* pUser); + +/// \~chinese +/// \brief 消息通道事件回调注册 +/// \param handle [IN] 设备句柄 +/// \param proc [IN] 消息通道事件回调注册函数 +/// \param pUser [IN] 用户自定义数据, 可设为NULL +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持一个回调函数,且设备关闭后,注册会失效,打开设备后需重新注册 +/// \~english +/// \brief Register call back function of message channel event. +/// \param handle [IN] Device handle +/// \param proc [IN] Call back function of message channel event +/// \param pUser [IN] User defined data,It can be set to NULL +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only one call back function is supported.\n +/// Registration becomes invalid after the device is closed, , and need to re-register after the device is opened +IMV_API int IMV_CALL IMV_SubscribeMsgChannelArg(IN IMV_HANDLE handle, IN IMV_MsgChannelCallBack proc, IN void* pUser); + +/// \~chinese +/// \brief 设置帧数据缓存个数 +/// \param handle [IN] 设备句柄 +/// \param nSize [IN] 缓存数量 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 不能在拉流过程中设置 +/// \~english +/// \brief Set frame buffer count +/// \param handle [IN] Device handle +/// \param nSize [IN] The buffer count +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// It can not be set during frame grabbing +IMV_API int IMV_CALL IMV_SetBufferCount(IN IMV_HANDLE handle, IN unsigned int nSize); + +/// \~chinese +/// \brief 清除帧数据缓存 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Clear frame buffer +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ClearFrameBuffer(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 设置驱动包间隔时间(MS),仅对Gige设备有效 +/// \param handle [IN] 设备句柄 +/// \param nTimeout [IN] 包间隔时间,单位是毫秒 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 触发模式尾包丢失重传机制 +/// \~english +/// \brief Set packet timeout(MS), only for Gige device +/// \param handle [IN] Device handle +/// \param nTimeout [IN] Time out value, unit is MS +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// The resend mechanism of tail packet loss on trigger mode +IMV_API int IMV_CALL IMV_GIGE_SetInterPacketTimeout(IN IMV_HANDLE handle, IN unsigned int nTimeout); + +/// \~chinese +/// \brief 设置单次重传最大包个数, 仅对GigE设备有效 +/// \param handle [IN] 设备句柄 +/// \param maxPacketNum [IN] 单次重传最大包个数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// maxPacketNum为0时,该功能无效 +/// \~english +/// \brief Set the single resend maximum packet number, only for Gige device +/// \param handle [IN] Device handle +/// \param maxPacketNum [IN] The value of single resend maximum packet number +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Disable the function when maxPacketNum is 0 +IMV_API int IMV_CALL IMV_GIGE_SetSingleResendMaxPacketNum(IN IMV_HANDLE handle, IN unsigned int maxPacketNum); + +/// \~chinese +/// \brief 设置同一帧最大丢包的数量,仅对GigE设备有效 +/// \param handle [IN] 设备句柄 +/// \param maxLostPacketNum [IN] 最大丢包的数量 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// maxLostPacketNum为0时,该功能无效 +/// \~english +/// \brief Set the maximum lost packet number, only for Gige device +/// \param handle [IN] Device handle +/// \param maxLostPacketNum [IN] The value of maximum lost packet number +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Disable the function when maxLostPacketNum is 0 +IMV_API int IMV_CALL IMV_GIGE_SetMaxLostPacketNum(IN IMV_HANDLE handle, IN unsigned int maxLostPacketNum); + +/// \~chinese +/// \brief 设置U3V设备的传输数据块的数量和大小,仅对USB设备有效 +/// \param handle [IN] 设备句柄 +/// \param nNum [IN] 传输数据块的数量(范围:5-256) +/// \param nSize [IN] 传输数据块的大小(范围:8-512, 单位:KByte) +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 1、该接口暂时只有在Linux平台且使用无驱的情况下设置才有效,其他情况下返回IMV_NOT_SUPPORT错误码\n +/// 2、传输数据块数量,范围5 - 256, 默认为64,高分辨率高帧率时可以适当增加该值;多台相机共同使用时,可以适当减小该值\n +/// 3、传输每个数据块大小,范围8 - 512, 默认为64,单位是KByte +/// \~english +/// \brief Set the number and size of urb transmitted, only for USB device +/// \param handle [IN] Device handle +/// \param nNum [IN] The number of urb transmitted(range:5-256) +/// \param nSize [IN] The size of urb transmitted(range:8-512, unit:KByte) +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// 1、The interface is only supported on the Linux platform without USB driver. In other cases, it returns IMV_NOT_SUPPORT error code.\n +/// 2、The number of urb transmitted, the range is 5 - 256, and the default is 64. when high pixel and high frame rate can be appropriately increased.; +/// when multiple cameras are used together, the value can be appropriately reduced.\n +/// 3、The size of each urb transmitted, the range is 8 - 512, the default is 64, the unit is KByte. +IMV_API int IMV_CALL IMV_USB_SetUrbTransfer(IN IMV_HANDLE handle, IN unsigned int nNum, IN unsigned int nSize); + +/// \~chinese +/// \brief 开始取流 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Start grabbing +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_StartGrabbing(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 开始取流 +/// \param handle [IN] 设备句柄 +/// \param maxImagesGrabbed [IN] 允许最多的取帧数,达到指定取帧数后停止取流,如果为0,表示忽略此参数连续取流(IMV_StartGrabbing默认0) +/// \param strategy [IN] 取流策略,(IMV_StartGrabbing默认使用grabStrartegySequential策略取流) +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Start grabbing +/// \param handle [IN] Device handle +/// \param maxImagesGrabbed [IN] Maximum images allowed to grab, once it reaches the limit then stop grabbing; +/// If it is 0, then ignore this parameter and start grabbing continuously(default 0 in IMV_StartGrabbing) +/// \param strategy [IN] Image grabbing strategy; (Default grabStrartegySequential in IMV_StartGrabbing) +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_StartGrabbingEx(IN IMV_HANDLE handle, IN uint64_t maxImagesGrabbed, IN IMV_EGrabStrategy strategy); + +/// \~chinese +/// \brief 判断设备是否正在取流 +/// \param handle [IN] 设备句柄 +/// \return 正在取流,返回true;不在取流,返回false +/// \~english +/// \brief Check whether device is grabbing or not +/// \param handle [IN] Device handle +/// \return Grabbing, return true. Not grabbing, return false +IMV_API bool IMV_CALL IMV_IsGrabbing(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 停止取流 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Stop grabbing +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_StopGrabbing(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 注册帧数据回调函数(异步获取帧数据机制) +/// \param handle [IN] 设备句柄 +/// \param proc [IN] 帧数据信息回调函数,建议不要在该函数中处理耗时的操作,否则会阻塞后续帧数据的实时性 +/// \param pUser [IN] 用户自定义数据, 可设为NULL +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 该异步获取帧数据机制和同步获取帧数据机制(IMV_GetFrame)互斥,对于同一设备,系统中两者只能选其一\n +/// 只支持一个回调函数, 且设备关闭后,注册会失效,打开设备后需重新注册 +/// \~english +/// \brief Register frame data callback function( asynchronous getting frame data mechanism); +/// \param handle [IN] Device handle +/// \param proc [IN] Frame data information callback function; It is advised to not put time-cosuming operation in this function, +/// otherwise it will block follow-up data frames and affect real time performance +/// \param pUser [IN] User defined data,It can be set to NULL +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// This asynchronous getting frame data mechanism and synchronous getting frame data mechanism(IMV_GetFrame) are mutually exclusive,\n +/// only one method can be choosed between these two in system for the same device.\n +/// Only one call back function is supported.\n +/// Registration becomes invalid after the device is closed, , and need to re-register after the device is opened +IMV_API int IMV_CALL IMV_AttachGrabbing(IN IMV_HANDLE handle, IN IMV_FrameCallBack proc, IN void* pUser); + +/// \~chinese +/// \brief 获取一帧图像(同步获取帧数据机制) +/// \param handle [IN] 设备句柄 +/// \param pFrame [OUT] 帧数据信息 +/// \param timeoutMS [IN] 获取一帧图像的超时时间,INFINITE时表示无限等待,直到收到一帧数据或者停止取流。单位是毫秒 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 该接口不支持多线程调用。\n +/// 该同步获取帧机制和异步获取帧机制(IMV_AttachGrabbing)互斥,对于同一设备,系统中两者只能选其一。\n +/// 使用内部缓存获取图像,需要IMV_ReleaseFrame进行释放图像缓存。 +/// \~english +/// \brief Get a frame image(synchronous getting frame data mechanism) +/// \param handle [IN] Device handle +/// \param pFrame [OUT] Frame data information +/// \param timeoutMS [IN] The time out of getting one image, INFINITE means infinite wait until the one frame data is returned or stop grabbing.unit is MS +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// This interface does not support multi-threading.\n +/// This synchronous getting frame data mechanism and asynchronous getting frame data mechanism(IMV_AttachGrabbing) are mutually exclusive,\n +/// only one method can be chose between these two in system for the same device.\n +/// Use internal cache to get image, need to release image buffer by IMV_ReleaseFrame +IMV_API int IMV_CALL IMV_GetFrame(IN IMV_HANDLE handle, OUT IMV_Frame* pFrame, IN unsigned int timeoutMS); + +/// \~chinese +/// \brief 释放图像缓存 +/// \param handle [IN] 设备句柄 +/// \param pFrame [IN] 帧数据信息 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Free image buffer +/// \param handle [IN] Device handle +/// \param pFrame [IN] Frame image data information +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ReleaseFrame(IN IMV_HANDLE handle, IN IMV_Frame* pFrame); + +/// \~chinese +/// \brief 帧数据深拷贝克隆 +/// \param handle [IN] 设备句柄 +/// \param pFrame [IN] 克隆源帧数据信息 +/// \param pCloneFrame [OUT] 新的帧数据信息 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 使用IMV_ReleaseFrame进行释放图像缓存。 +/// \~english +/// \brief Frame data deep clone +/// \param handle [IN] Device handle +/// \param pFrame [IN] Frame data information of clone source +/// \param pCloneFrame [OUT] New frame data information +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Use IMV_ReleaseFrame to free image buffer + +IMV_API int IMV_CALL IMV_CloneFrame(IN IMV_HANDLE handle, IN IMV_Frame* pFrame, OUT IMV_Frame* pCloneFrame); + +/// \~chinese +/// \brief 获取Chunk数据(仅对GigE/Usb相机有效) +/// \param handle [IN] 设备句柄 +/// \param pFrame [IN] 帧数据信息 +/// \param index [IN] 索引ID +/// \param pChunkDataInfo [OUT] Chunk数据信息 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get chunk data(Only GigE/Usb Camera) +/// \param handle [IN] Device handle +/// \param pFrame [IN] Frame data information +/// \param index [IN] index ID +/// \param pChunkDataInfo [OUT] Chunk data infomation +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetChunkDataByIndex(IN IMV_HANDLE handle, IN IMV_Frame* pFrame, IN unsigned int index, OUT IMV_ChunkDataInfo *pChunkDataInfo); + +/// \~chinese +/// \brief 获取流统计信息(IMV_StartGrabbing / IMV_StartGrabbing执行后调用) +/// \param handle [IN] 设备句柄 +/// \param pStreamStatsInfo [OUT] 流统计信息数据 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get stream statistics infomation(Used after excuting IMV_StartGrabbing / IMV_StartGrabbing) +/// \param handle [IN] Device handle +/// \param pStreamStatsInfo [OUT] Stream statistics infomation +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetStatisticsInfo(IN IMV_HANDLE handle, OUT IMV_StreamStatisticsInfo* pStreamStatsInfo); + +/// \~chinese +/// \brief 重置流统计信息(IMV_StartGrabbing / IMV_StartGrabbing执行后调用) +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Reset stream statistics infomation(Used after excuting IMV_StartGrabbing / IMV_StartGrabbing) +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ResetStatisticsInfo(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 判断属性是否可用 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 可用,返回true;不可用,返回false +/// \~english +/// \brief Check the property is available or not +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Available, return true. Not available, return false +IMV_API bool IMV_CALL IMV_FeatureIsAvailable(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 判断属性是否可读 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 可读,返回true;不可读,返回false +/// \~english +/// \brief Check the property is readable or not +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Readable, return true. Not readable, return false +IMV_API bool IMV_CALL IMV_FeatureIsReadable(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 判断属性是否可写 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 可写,返回true;不可写,返回false +/// \~english +/// \brief Check the property is writeable or not +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Writeable, return true. Not writeable, return false +IMV_API bool IMV_CALL IMV_FeatureIsWriteable(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 判断属性是否可流 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 可流,返回true;不可流,返回false +/// \~english +/// \brief Check the property is streamable or not +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Streamable, return true. Not streamable, return false +IMV_API bool IMV_CALL IMV_FeatureIsStreamable(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 判断属性是否有效 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 有效,返回true;无效,返回false +/// \~english +/// \brief Check the property is valid or not +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Valid, return true. Invalid, return false +IMV_API bool IMV_CALL IMV_FeatureIsValid(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 获取整型属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pIntValue [OUT] 整型属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get integer property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pIntValue [OUT] Integer property value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetIntFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); + +/// \~chinese +/// \brief 获取整型属性可设的最小值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pIntValue [OUT] 整型属性可设的最小值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get the integer property settable minimum value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pIntValue [OUT] Integer property settable minimum value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetIntFeatureMin(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); + +/// \~chinese +/// \brief 获取整型属性可设的最大值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pIntValue [OUT] 整型属性可设的最大值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get the integer property settable maximum value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pIntValue [OUT] Integer property settable maximum value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetIntFeatureMax(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); + +/// \~chinese +/// \brief 获取整型属性步长 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pIntValue [OUT] 整型属性步长 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get integer property increment +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pIntValue [OUT] Integer property increment +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetIntFeatureInc(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); + +/// \~chinese +/// \brief 设置整型属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param intValue [IN] 待设置的整型属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set integer property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param intValue [IN] Integer property value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetIntFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, IN int64_t intValue); + +/// \~chinese +/// \brief 获取浮点属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pDoubleValue [OUT] 浮点属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get double property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pDoubleValue [OUT] Double property value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetDoubleFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); + +/// \~chinese +/// \brief 获取浮点属性可设的最小值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pDoubleValue [OUT] 浮点属性可设的最小值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get the double property settable minimum value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pDoubleValue [OUT] Double property settable minimum value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetDoubleFeatureMin(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); + +/// \~chinese +/// \brief 获取浮点属性可设的最大值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pDoubleValue [OUT] 浮点属性可设的最大值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get the double property settable maximum value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pDoubleValue [OUT] Double property settable maximum value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetDoubleFeatureMax(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); + +/// \~chinese +/// \brief 设置浮点属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param doubleValue [IN] 待设置的浮点属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set double property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param doubleValue [IN] Double property value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetDoubleFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, IN double doubleValue); + +/// \~chinese +/// \brief 获取布尔属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pBoolValue [OUT] 布尔属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get boolean property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pBoolValue [OUT] Boolean property value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetBoolFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT bool* pBoolValue); + +/// \~chinese +/// \brief 设置布尔属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param boolValue [IN] 待设置的布尔属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set boolean property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param boolValue [IN] Boolean property value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetBoolFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, IN bool boolValue); + +/// \~chinese +/// \brief 获取枚举属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pEnumValue [OUT] 枚举属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get enumeration property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pEnumValue [OUT] Enumeration property value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetEnumFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT uint64_t* pEnumValue); + +/// \~chinese +/// \brief 设置枚举属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param enumValue [IN] 待设置的枚举属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set enumeration property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param enumValue [IN] Enumeration property value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetEnumFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, IN uint64_t enumValue); + +/// \~chinese +/// \brief 获取枚举属性symbol值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pEnumSymbol [OUT] 枚举属性symbol值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get enumeration property symbol value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pEnumSymbol [OUT] Enumeration property symbol value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetEnumFeatureSymbol(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT IMV_String* pEnumSymbol); + +/// \~chinese +/// \brief 设置枚举属性symbol值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pEnumSymbol [IN] 待设置的枚举属性symbol值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set enumeration property symbol value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pEnumSymbol [IN] Enumeration property symbol value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetEnumFeatureSymbol(IN IMV_HANDLE handle, IN const char* pFeatureName, IN const char* pEnumSymbol); + +/// \~chinese +/// \brief 获取枚举属性的可设枚举值的个数 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pEntryNum [OUT] 枚举属性的可设枚举值的个数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get the number of enumeration property settable enumeration +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pEntryNum [OUT] The number of enumeration property settable enumeration value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetEnumFeatureEntryNum(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT unsigned int* pEntryNum); + +/// \~chinese +/// \brief 获取枚举属性的可设枚举值列表 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pEnumEntryList [OUT] 枚举属性的可设枚举值列表 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get settable enumeration value list of enumeration property +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pEnumEntryList [OUT] Settable enumeration value list of enumeration property +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetEnumFeatureEntrys(IN IMV_HANDLE handle, IN const char* pFeatureName, IN_OUT IMV_EnumEntryList* pEnumEntryList); + +/// \~chinese +/// \brief 获取字符串属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pStringValue [OUT] 字符串属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get string property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pStringValue [OUT] String property value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetStringFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT IMV_String* pStringValue); + +/// \~chinese +/// \brief 设置字符串属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pStringValue [IN] 待设置的字符串属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set string property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pStringValue [IN] String property value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetStringFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, IN const char* pStringValue); + +/// \~chinese +/// \brief 执行命令属性 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Execute command property +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ExecuteCommandFeature(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 像素格式转换 +/// \param handle [IN] 设备句柄 +/// \param pstPixelConvertParam [IN][OUT] 像素格式转换参数结构体 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持转化成目标像素格式gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8 / gvspPixelBGRA8\n +/// 通过该接口将原始图像数据转换成用户所需的像素格式并存放在调用者指定内存中。\n +/// 像素格式为YUV411Packed的时,图像宽须能被4整除\n +/// 像素格式为YUV422Packed的时,图像宽须能被2整除\n +/// 像素格式为YUYVPacked的时,图像宽须能被2整除\n +/// 转换后的图像:数据存储是从最上面第一行开始的,这个是相机数据的默认存储方向 +/// \~english +/// \brief Pixel format conversion +/// \param handle [IN] Device handle +/// \param pstPixelConvertParam [IN][OUT] Convert Pixel Type parameter structure +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only support converting to destination pixel format of gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8 / gvspPixelBGRA8\n +/// This API is used to transform the collected original data to pixel format and save to specified memory by caller.\n +/// pixelFormat:YUV411Packed, the image width is divisible by 4\n +/// pixelFormat : YUV422Packed, the image width is divisible by 2\n +/// pixelFormat : YUYVPacked,the image width is divisible by 2\n +/// converted image:The first row of the image is located at the start of the image buffer.This is the default for image taken by a camera. +IMV_API int IMV_CALL IMV_PixelConvert(IN IMV_HANDLE handle, IN_OUT IMV_PixelConvertParam* pstPixelConvertParam); + +/// \~chinese +/// \brief 打开录像 +/// \param handle [IN] 设备句柄 +/// \param pstRecordParam [IN] 录像参数结构体 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Open record +/// \param handle [IN] Device handle +/// \param pstRecordParam [IN] Record param structure +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_OpenRecord(IN IMV_HANDLE handle, IN IMV_RecordParam *pstRecordParam); + +/// \~chinese +/// \brief 录制一帧图像 +/// \param handle [IN] 设备句柄 +/// \param pstRecordFrameInfoParam [IN] 录像用帧信息结构体 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Record one frame +/// \param handle [IN] Device handle +/// \param pstRecordFrameInfoParam [IN] Frame information for recording structure +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_InputOneFrame(IN IMV_HANDLE handle, IN IMV_RecordFrameInfoParam *pstRecordFrameInfoParam); + +/// \~chinese +/// \brief 关闭录像 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Close record +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_CloseRecord(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 图像翻转 +/// \param handle [IN] 设备句柄 +/// \param pstFlipImageParam [IN][OUT] 图像翻转参数结构体 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持像素格式gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8的图像的垂直和水平翻转。\n +/// 通过该接口将原始图像数据翻转后并存放在调用者指定内存中。 +/// \~english +/// \brief Flip image +/// \param handle [IN] Device handle +/// \param pstFlipImageParam [IN][OUT] Flip image parameter structure +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only support vertical and horizontal flip of image data with gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8 pixel format.\n +/// This API is used to flip original data and save to specified memory by caller. +IMV_API int IMV_CALL IMV_FlipImage(IN IMV_HANDLE handle, IN_OUT IMV_FlipImageParam* pstFlipImageParam); + +/// \~chinese +/// \brief 图像顺时针旋转 +/// \param handle [IN] 设备句柄 +/// \param pstRotateImageParam [IN][OUT] 图像旋转参数结构体 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8格式数据的90/180/270度顺时针旋转。\n +/// 通过该接口将原始图像数据旋转后并存放在调用者指定内存中。 +/// \~english +/// \brief Rotate image clockwise +/// \param handle [IN] Device handle +/// \param pstRotateImageParam [IN][OUT] Rotate image parameter structure +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only support 90/180/270 clockwise rotation of data in the gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8 format.\n +/// This API is used to rotation original data and save to specified memory by caller. +IMV_API int IMV_CALL IMV_RotateImage(IN IMV_HANDLE handle, IN_OUT IMV_RotateImageParam* pstRotateImageParam); + +#ifdef __cplusplus +} +#endif + +#endif // __IMV_API_H__ \ No newline at end of file diff --git a/camera_driver/IMVDefines.h b/camera_driver/IMVDefines.h new file mode 100644 index 0000000..bb1386d --- /dev/null +++ b/camera_driver/IMVDefines.h @@ -0,0 +1,811 @@ +#ifndef __IMV_DEFINES_H__ +#define __IMV_DEFINES_H__ + +#ifdef WIN32 +typedef __int64 int64_t; +typedef unsigned __int64 uint64_t; +#else +#include +#endif + +#ifndef IN +#define IN ///< \~chinese 输入型参数 \~english Input param +#endif + +#ifndef OUT +#define OUT ///< \~chinese 输出型参数 \~english Output param +#endif + +#ifndef IN_OUT +#define IN_OUT ///< \~chinese 输入/输出型参数 \~english Input/Output param +#endif + +#ifndef __cplusplus +typedef char bool; +#define true 1 +#define false 0 +#endif + +/// \~chinese +/// \brief 错误码 +/// \~english +/// \brief Error code +#define IMV_OK 0 ///< \~chinese 成功,无错误 \~english Successed, no error +#define IMV_ERROR -101 ///< \~chinese 通用的错误 \~english Generic error +#define IMV_INVALID_HANDLE -102 ///< \~chinese 错误或无效的句柄 \~english Error or invalid handle +#define IMV_INVALID_PARAM -103 ///< \~chinese 错误的参数 \~english Incorrect parameter +#define IMV_INVALID_FRAME_HANDLE -104 ///< \~chinese 错误或无效的帧句柄 \~english Error or invalid frame handle +#define IMV_INVALID_FRAME -105 ///< \~chinese 无效的帧 \~english Invalid frame +#define IMV_INVALID_RESOURCE -106 ///< \~chinese 相机/事件/流等资源无效 \~english Camera/Event/Stream and so on resource invalid +#define IMV_INVALID_IP -107 ///< \~chinese 设备与主机的IP网段不匹配 \~english Device's and PC's subnet is mismatch +#define IMV_NO_MEMORY -108 ///< \~chinese 内存不足 \~english Malloc memery failed +#define IMV_INSUFFICIENT_MEMORY -109 ///< \~chinese 传入的内存空间不足 \~english Insufficient memory +#define IMV_ERROR_PROPERTY_TYPE -110 ///< \~chinese 属性类型错误 \~english Property type error +#define IMV_INVALID_ACCESS -111 ///< \~chinese 属性不可访问、或不能读/写、或读/写失败 \~english Property not accessible, or not be read/written, or read/written failed +#define IMV_INVALID_RANGE -112 ///< \~chinese 属性值超出范围、或者不是步长整数倍 \~english The property's value is out of range, or is not integer multiple of the step +#define IMV_NOT_SUPPORT -113 ///< \~chinese 设备不支持的功能 \~english Device not supported function + +#define IMV_MAX_DEVICE_ENUM_NUM 100 ///< \~chinese 支持设备最大个数 \~english The maximum number of supported devices +#define IMV_MAX_STRING_LENTH 256 ///< \~chinese 字符串最大长度 \~english The maximum length of string +#define IMV_MAX_ERROR_LIST_NUM 128 ///< \~chinese 失败属性列表最大长度 \~english The maximum size of failed properties list + +typedef void* IMV_HANDLE; ///< \~chinese 设备句柄 \~english Device handle +typedef void* IMV_FRAME_HANDLE; ///< \~chinese 帧句柄 \~english Frame handle + +/// \~chinese +///枚举:接口类型 +/// \~english +///Enumeration: interface type +typedef enum _IMV_EInterfaceType +{ + interfaceTypeGige = 0x00000001, ///< \~chinese 网卡接口类型 \~english NIC type + interfaceTypeUsb3 = 0x00000002, ///< \~chinese USB3.0接口类型 \~english USB3.0 interface type + interfaceTypeCL = 0x00000004, ///< \~chinese CAMERALINK接口类型 \~english Cameralink interface type + interfaceTypePCIe = 0x00000008, ///< \~chinese PCIe接口类型 \~english PCIe interface type + interfaceTypeAll = 0x00000000, ///< \~chinese 忽略接口类型 \~english All types interface type + interfaceInvalidType = 0xFFFFFFFF ///< \~chinese 无效接口类型 \~english Invalid interface type +}IMV_EInterfaceType; + +/// \~chinese +///枚举:设备类型 +/// \~english +///Enumeration: device type +typedef enum _IMV_ECameraType +{ + typeGigeCamera = 0, ///< \~chinese GIGE相机 \~english GigE Vision Camera + typeU3vCamera = 1, ///< \~chinese USB3.0相机 \~english USB3.0 Vision Camera + typeCLCamera = 2, ///< \~chinese CAMERALINK 相机 \~english Cameralink camera + typePCIeCamera = 3, ///< \~chinese PCIe相机 \~english PCIe Camera + typeUndefinedCamera = 255 ///< \~chinese 未知类型 \~english Undefined Camera +}IMV_ECameraType; + +/// \~chinese +///枚举:创建句柄方式 +/// \~english +///Enumeration: Create handle mode +typedef enum _IMV_ECreateHandleMode +{ + modeByIndex = 0, ///< \~chinese 通过已枚举设备的索引(从0开始,比如 0, 1, 2...) \~english By index of enumerated devices (Start from 0, such as 0, 1, 2...) + modeByCameraKey, ///< \~chinese 通过设备键"厂商:序列号" \~english By device's key "vendor:serial number" + modeByDeviceUserID, ///< \~chinese 通过设备自定义名 \~english By device userID + modeByIPAddress, ///< \~chinese 通过设备IP地址 \~english By device IP address. +}IMV_ECreateHandleMode; + +/// \~chinese +///枚举:访问权限 +/// \~english +///Enumeration: access permission +typedef enum _IMV_ECameraAccessPermission +{ + accessPermissionOpen = 0, ///< \~chinese GigE相机没有被连接 \~english The GigE vision device isn't connected to any application. + accessPermissionExclusive, ///< \~chinese 独占访问权限 \~english Exclusive Access Permission + accessPermissionControl, ///< \~chinese 非独占可读访问权限 \~english Non-Exclusive Readbale Access Permission + accessPermissionControlWithSwitchover, ///< \~chinese 切换控制访问权限 \~english Control access with switchover enabled. + accessPermissionUnknown = 254, ///< \~chinese 无法确定 \~english Value not known; indeterminate. + accessPermissionUndefined ///< \~chinese 未定义访问权限 \~english Undefined Access Permission +}IMV_ECameraAccessPermission; + +/// \~chinese +///枚举:抓图策略 +/// \~english +///Enumeration: grab strartegy +typedef enum _IMV_EGrabStrategy +{ + grabStrartegySequential = 0, ///< \~chinese 按到达顺序处理图片 \~english The images are processed in the order of their arrival + grabStrartegyLatestImage = 1, ///< \~chinese 获取最新的图片 \~english Get latest image + grabStrartegyUpcomingImage = 2, ///< \~chinese 等待获取下一张图片(只针对GigE相机) \~english Waiting for next image(GigE only) + grabStrartegyUndefined ///< \~chinese 未定义 \~english Undefined +}IMV_EGrabStrategy; + +/// \~chinese +///枚举:流事件状态 +/// \~english +/// Enumeration:stream event status +typedef enum _IMV_EEventStatus +{ + streamEventNormal = 1, ///< \~chinese 正常流事件 \~english Normal stream event + streamEventLostFrame = 2, ///< \~chinese 丢帧事件 \~english Lost frame event + streamEventLostPacket = 3, ///< \~chinese 丢包事件 \~english Lost packet event + streamEventImageError = 4, ///< \~chinese 图像错误事件 \~english Error image event + streamEventStreamChannelError = 5, ///< \~chinese 取流错误事件 \~english Stream channel error event + streamEventTooManyConsecutiveResends = 6, ///< \~chinese 太多连续重传 \~english Too many consecutive resends event + streamEventTooManyLostPacket = 7 ///< \~chinese 太多丢包 \~english Too many lost packet event +}IMV_EEventStatus; + +/// \~chinese +///枚举:图像转换Bayer格式所用的算法 +/// \~english +/// Enumeration:alorithm used for Bayer demosaic +typedef enum _IMV_EBayerDemosaic +{ + demosaicNearestNeighbor, ///< \~chinese 最近邻 \~english Nearest neighbor + demosaicBilinear, ///< \~chinese 双线性 \~english Bilinear + demosaicEdgeSensing, ///< \~chinese 边缘检测 \~english Edge sensing + demosaicNotSupport = 255, ///< \~chinese 不支持 \~english Not support +}IMV_EBayerDemosaic; + +/// \~chinese +///枚举:事件类型 +/// \~english +/// Enumeration:event type +typedef enum _IMV_EVType +{ + offLine, ///< \~chinese 设备离线通知 \~english device offline notification + onLine ///< \~chinese 设备在线通知 \~english device online notification +}IMV_EVType; + +/// \~chinese +///枚举:视频格式 +/// \~english +/// Enumeration:Video format +typedef enum _IMV_EVideoType +{ + typeVideoFormatAVI = 0, ///< \~chinese AVI格式 \~english AVI format + typeVideoFormatNotSupport = 255 ///< \~chinese 不支持 \~english Not support +}IMV_EVideoType; + +/// \~chinese +///枚举:图像翻转类型 +/// \~english +/// Enumeration:Image flip type +typedef enum _IMV_EFlipType +{ + typeFlipVertical, ///< \~chinese 垂直(Y轴)翻转 \~english Vertical(Y-axis) flip + typeFlipHorizontal ///< \~chinese 水平(X轴)翻转 \~english Horizontal(X-axis) flip +}IMV_EFlipType; + +/// \~chinese +///枚举:顺时针旋转角度 +/// \~english +/// Enumeration:Rotation angle clockwise +typedef enum _IMV_ERotationAngle +{ + rotationAngle90, ///< \~chinese 顺时针旋转90度 \~english Rotate 90 degree clockwise + rotationAngle180, ///< \~chinese 顺时针旋转180度 \~english Rotate 180 degree clockwise + rotationAngle270, ///< \~chinese 顺时针旋转270度 \~english Rotate 270 degree clockwise +}IMV_ERotationAngle; + +#define IMV_GVSP_PIX_MONO 0x01000000 +#define IMV_GVSP_PIX_RGB 0x02000000 +#define IMV_GVSP_PIX_COLOR 0x02000000 +#define IMV_GVSP_PIX_CUSTOM 0x80000000 +#define IMV_GVSP_PIX_COLOR_MASK 0xFF000000 + +// Indicate effective number of bits occupied by the pixel (including padding). +// This can be used to compute amount of memory required to store an image. +#define IMV_GVSP_PIX_OCCUPY1BIT 0x00010000 +#define IMV_GVSP_PIX_OCCUPY2BIT 0x00020000 +#define IMV_GVSP_PIX_OCCUPY4BIT 0x00040000 +#define IMV_GVSP_PIX_OCCUPY8BIT 0x00080000 +#define IMV_GVSP_PIX_OCCUPY12BIT 0x000C0000 +#define IMV_GVSP_PIX_OCCUPY16BIT 0x00100000 +#define IMV_GVSP_PIX_OCCUPY24BIT 0x00180000 +#define IMV_GVSP_PIX_OCCUPY32BIT 0x00200000 +#define IMV_GVSP_PIX_OCCUPY36BIT 0x00240000 +#define IMV_GVSP_PIX_OCCUPY48BIT 0x00300000 + +/// \~chinese +///枚举:图像格式 +/// \~english +/// Enumeration:image format +typedef enum _IMV_EPixelType +{ + // Undefined pixel type + gvspPixelTypeUndefined = -1, + + // Mono Format + gvspPixelMono1p = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY1BIT | 0x0037), + gvspPixelMono2p = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY2BIT | 0x0038), + gvspPixelMono4p = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY4BIT | 0x0039), + gvspPixelMono8 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x0001), + gvspPixelMono8S = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x0002), + gvspPixelMono10 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0003), + gvspPixelMono10Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0004), + gvspPixelMono12 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0005), + gvspPixelMono12Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0006), + gvspPixelMono14 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0025), + gvspPixelMono16 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0007), + + // Bayer Format + gvspPixelBayGR8 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x0008), + gvspPixelBayRG8 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x0009), + gvspPixelBayGB8 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x000A), + gvspPixelBayBG8 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x000B), + gvspPixelBayGR10 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x000C), + gvspPixelBayRG10 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x000D), + gvspPixelBayGB10 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x000E), + gvspPixelBayBG10 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x000F), + gvspPixelBayGR12 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0010), + gvspPixelBayRG12 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0011), + gvspPixelBayGB12 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0012), + gvspPixelBayBG12 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0013), + gvspPixelBayGR10Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0026), + gvspPixelBayRG10Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0027), + gvspPixelBayGB10Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0028), + gvspPixelBayBG10Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0029), + gvspPixelBayGR12Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x002A), + gvspPixelBayRG12Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x002B), + gvspPixelBayGB12Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x002C), + gvspPixelBayBG12Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x002D), + gvspPixelBayGR16 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x002E), + gvspPixelBayRG16 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x002F), + gvspPixelBayGB16 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0030), + gvspPixelBayBG16 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0031), + + // RGB Format + gvspPixelRGB8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x0014), + gvspPixelBGR8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x0015), + gvspPixelRGBA8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY32BIT | 0x0016), + gvspPixelBGRA8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY32BIT | 0x0017), + gvspPixelRGB10 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0018), + gvspPixelBGR10 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0019), + gvspPixelRGB12 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x001A), + gvspPixelBGR12 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x001B), + gvspPixelRGB16 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0033), + gvspPixelRGB10V1Packed = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY32BIT | 0x001C), + gvspPixelRGB10P32 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY32BIT | 0x001D), + gvspPixelRGB12V1Packed = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY36BIT | 0X0034), + gvspPixelRGB565P = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0035), + gvspPixelBGR565P = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0X0036), + + // YVR Format + gvspPixelYUV411_8_UYYVYY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY12BIT | 0x001E), + gvspPixelYUV422_8_UYVY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x001F), + gvspPixelYUV422_8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0032), + gvspPixelYUV8_UYV = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x0020), + gvspPixelYCbCr8CbYCr = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x003A), + gvspPixelYCbCr422_8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x003B), + gvspPixelYCbCr422_8_CbYCrY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0043), + gvspPixelYCbCr411_8_CbYYCrYY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY12BIT | 0x003C), + gvspPixelYCbCr601_8_CbYCr = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x003D), + gvspPixelYCbCr601_422_8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x003E), + gvspPixelYCbCr601_422_8_CbYCrY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0044), + gvspPixelYCbCr601_411_8_CbYYCrYY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY12BIT | 0x003F), + gvspPixelYCbCr709_8_CbYCr = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x0040), + gvspPixelYCbCr709_422_8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0041), + gvspPixelYCbCr709_422_8_CbYCrY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0045), + gvspPixelYCbCr709_411_8_CbYYCrYY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY12BIT | 0x0042), + + // RGB Planar + gvspPixelRGB8Planar = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x0021), + gvspPixelRGB10Planar = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0022), + gvspPixelRGB12Planar = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0023), + gvspPixelRGB16Planar = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0024), + + //BayerRG10p和BayerRG12p格式,针对特定项目临时添加,请不要使用 + //BayerRG10p and BayerRG12p, currently used for specific project, please do not use them + gvspPixelBayRG10p = 0x010A0058, + gvspPixelBayRG12p = 0x010c0059, + + //mono1c格式,自定义格式 + //mono1c, customized image format, used for binary output + gvspPixelMono1c = 0x012000FF, + + //mono1e格式,自定义格式,用来显示连通域 + //mono1e, customized image format, used for displaying connected domain + gvspPixelMono1e = 0x01080FFF +}IMV_EPixelType; + +/// \~chinese +/// \brief 字符串信息 +/// \~english +/// \brief String information +typedef struct _IMV_String +{ + char str[IMV_MAX_STRING_LENTH]; ///< \~chinese 字符串.长度不超过256 \~english Strings and the maximum length of strings is 255. +}IMV_String; + +/// \~chinese +/// \brief GigE网卡信息 +/// \~english +/// \brief GigE interface information +typedef struct _IMV_GigEInterfaceInfo +{ + char description[IMV_MAX_STRING_LENTH]; ///< \~chinese 网卡描述信息 \~english Network card description + char macAddress[IMV_MAX_STRING_LENTH]; ///< \~chinese 网卡Mac地址 \~english Network card MAC Address + char ipAddress[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备Ip地址 \~english Device ip Address + char subnetMask[IMV_MAX_STRING_LENTH]; ///< \~chinese 子网掩码 \~english SubnetMask + char defaultGateWay[IMV_MAX_STRING_LENTH]; ///< \~chinese 默认网关 \~english Default GateWay + char chReserved[5][IMV_MAX_STRING_LENTH]; ///< 保留 \~english Reserved field +}IMV_GigEInterfaceInfo; + +/// \~chinese +/// \brief USB接口信息 +/// \~english +/// \brief USB interface information +typedef struct _IMV_UsbInterfaceInfo +{ + char description[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口描述信息 \~english USB interface description + char vendorID[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口Vendor ID \~english USB interface Vendor ID + char deviceID[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口设备ID \~english USB interface Device ID + char subsystemID[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口Subsystem ID \~english USB interface Subsystem ID + char revision[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口Revision \~english USB interface Revision + char speed[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口speed \~english USB interface speed + char chReserved[4][IMV_MAX_STRING_LENTH]; ///< 保留 \~english Reserved field +}IMV_UsbInterfaceInfo; + +/// \~chinese +/// \brief GigE设备信息 +/// \~english +/// \brief GigE device information +typedef struct _IMV_GigEDeviceInfo +{ + /// \~chinese + /// 设备支持的IP配置选项\n + /// value:4 相机只支持LLA\n + /// value:5 相机支持LLA和Persistent IP\n + /// value:6 相机支持LLA和DHCP\n + /// value:7 相机支持LLA、DHCP和Persistent IP\n + /// value:0 获取失败 + /// \~english + /// Supported IP configuration options of device\n + /// value:4 Device supports LLA \n + /// value:5 Device supports LLA and Persistent IP\n + /// value:6 Device supports LLA and DHCP\n + /// value:7 Device supports LLA, DHCP and Persistent IP\n + /// value:0 Get fail + unsigned int nIpConfigOptions; + /// \~chinese + /// 设备当前的IP配置选项\n + /// value:4 LLA处于活动状态\n + /// value:5 LLA和Persistent IP处于活动状态\n + /// value:6 LLA和DHCP处于活动状态\n + /// value:7 LLA、DHCP和Persistent IP处于活动状态\n + /// value:0 获取失败 + /// \~english + /// Current IP Configuration options of device\n + /// value:4 LLA is active\n + /// value:5 LLA and Persistent IP are active\n + /// value:6 LLA and DHCP are active\n + /// value:7 LLA, DHCP and Persistent IP are active\n + /// value:0 Get fail + unsigned int nIpConfigCurrent; + unsigned int nReserved[3]; ///< \~chinese 保留 \~english Reserved field + + char macAddress[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备Mac地址 \~english Device MAC Address + char ipAddress[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备Ip地址 \~english Device ip Address + char subnetMask[IMV_MAX_STRING_LENTH]; ///< \~chinese 子网掩码 \~english SubnetMask + char defaultGateWay[IMV_MAX_STRING_LENTH]; ///< \~chinese 默认网关 \~english Default GateWay + char protocolVersion[IMV_MAX_STRING_LENTH]; ///< \~chinese 网络协议版本 \~english Net protocol version + /// \~chinese + /// Ip配置有效性\n + /// Ip配置有效时字符串值"Valid"\n + /// Ip配置无效时字符串值"Invalid On This Interface" + /// \~english + /// IP configuration valid\n + /// String value is "Valid" when ip configuration valid\n + /// String value is "Invalid On This Interface" when ip configuration invalid + char ipConfiguration[IMV_MAX_STRING_LENTH]; + char chReserved[6][IMV_MAX_STRING_LENTH]; ///< \~chinese 保留 \~english Reserved field + +}IMV_GigEDeviceInfo; + +/// \~chinese +/// \brief Usb设备信息 +/// \~english +/// \brief Usb device information +typedef struct _IMV_UsbDeviceInfo +{ + bool bLowSpeedSupported; ///< \~chinese true支持,false不支持,其他值 非法。 \~english true support,false not supported,other invalid + bool bFullSpeedSupported; ///< \~chinese true支持,false不支持,其他值 非法。 \~english true support,false not supported,other invalid + bool bHighSpeedSupported; ///< \~chinese true支持,false不支持,其他值 非法。 \~english true support,false not supported,other invalid + bool bSuperSpeedSupported; ///< \~chinese true支持,false不支持,其他值 非法。 \~english true support,false not supported,other invalid + bool bDriverInstalled; ///< \~chinese true安装,false未安装,其他值 非法。 \~english true support,false not supported,other invalid + bool boolReserved[3]; ///< \~chinese 保留 + unsigned int Reserved[4]; ///< \~chinese 保留 \~english Reserved field + + char configurationValid[IMV_MAX_STRING_LENTH]; ///< \~chinese 配置有效性 \~english Configuration Valid + char genCPVersion[IMV_MAX_STRING_LENTH]; ///< \~chinese GenCP 版本 \~english GenCP Version + char u3vVersion[IMV_MAX_STRING_LENTH]; ///< \~chinese U3V 版本号 \~english U3v Version + char deviceGUID[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备引导号 \~english Device guid number + char familyName[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备系列号 \~english Device serial number + char u3vSerialNumber[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备序列号 \~english Device SerialNumber + char speed[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备传输速度 \~english Device transmission speed + char maxPower[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备最大供电量 \~english Maximum power supply of device + char chReserved[4][IMV_MAX_STRING_LENTH]; ///< \~chinese 保留 \~english Reserved field + +}IMV_UsbDeviceInfo; + +/// \~chinese +/// \brief 设备通用信息 +/// \~english +/// \brief Device general information +typedef struct _IMV_DeviceInfo +{ + IMV_ECameraType nCameraType; ///< \~chinese 设备类别 \~english Camera type + int nCameraReserved[5]; ///< \~chinese 保留 \~english Reserved field + + char cameraKey[IMV_MAX_STRING_LENTH]; ///< \~chinese 厂商:序列号 \~english Camera key + char cameraName[IMV_MAX_STRING_LENTH]; ///< \~chinese 用户自定义名 \~english UserDefinedName + char serialNumber[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备序列号 \~english Device SerialNumber + char vendorName[IMV_MAX_STRING_LENTH]; ///< \~chinese 厂商 \~english Camera Vendor + char modelName[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备型号 \~english Device model + char manufactureInfo[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备制造信息 \~english Device ManufactureInfo + char deviceVersion[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备版本 \~english Device Version + char cameraReserved[5][IMV_MAX_STRING_LENTH]; ///< \~chinese 保留 \~english Reserved field + union + { + IMV_GigEDeviceInfo gigeDeviceInfo; ///< \~chinese Gige设备信息 \~english Gige Device Information + IMV_UsbDeviceInfo usbDeviceInfo; ///< \~chinese Usb设备信息 \~english Usb Device Information + }DeviceSpecificInfo; + + IMV_EInterfaceType nInterfaceType; ///< \~chinese 接口类别 \~english Interface type + int nInterfaceReserved[5]; ///< \~chinese 保留 \~english Reserved field + char interfaceName[IMV_MAX_STRING_LENTH]; ///< \~chinese 接口名 \~english Interface Name + char interfaceReserved[5][IMV_MAX_STRING_LENTH]; ///< \~chinese 保留 \~english Reserved field + union + { + IMV_GigEInterfaceInfo gigeInterfaceInfo; ///< \~chinese GigE网卡信息 \~english Gige interface Information + IMV_UsbInterfaceInfo usbInterfaceInfo; ///< \~chinese Usb接口信息 \~english Usb interface Information + }InterfaceInfo; +}IMV_DeviceInfo; + +/// \~chinese +/// \brief 加载失败的属性信息 +/// \~english +/// \brief Load failed properties information +typedef struct _IMV_ErrorList +{ + unsigned int nParamCnt; ///< \~chinese 加载失败的属性个数 \~english The count of load failed properties + IMV_String paramNameList[IMV_MAX_ERROR_LIST_NUM]; ///< \~chinese 加载失败的属性集合,上限128 \~english Array of load failed properties, up to 128 +}IMV_ErrorList; + +/// \~chinese +/// \brief 设备信息列表 +/// \~english +/// \brief Device information list +typedef struct _IMV_DeviceList +{ + unsigned int nDevNum; ///< \~chinese 设备数量 \~english Device Number + IMV_DeviceInfo* pDevInfo; ///< \~chinese 设备息列表(SDK内部缓存),最多100设备 \~english Device information list(cached within the SDK), up to 100 +}IMV_DeviceList; + +/// \~chinese +/// \brief 连接事件信息 +/// \~english +/// \brief connection event information +typedef struct _IMV_SConnectArg +{ + IMV_EVType event; ///< \~chinese 事件类型 \~english event type + unsigned int nReserve[10]; ///< \~chinese 预留字段 \~english Reserved field +}IMV_SConnectArg; + +/// \~chinese +/// \brief 参数更新事件信息 +/// \~english +/// \brief Updating parameters event information +typedef struct _IMV_SParamUpdateArg +{ + bool isPoll; ///< \~chinese 是否是定时更新,true:表示是定时更新,false:表示非定时更新 \~english Update periodically or not. true:update periodically, true:not update periodically + unsigned int nReserve[10]; ///< \~chinese 预留字段 \~english Reserved field + unsigned int nParamCnt; ///< \~chinese 更新的参数个数 \~english The number of parameters which need update + IMV_String* pParamNameList; ///< \~chinese 更新的参数名称集合(SDK内部缓存) \~english Array of parameter's name which need to be updated(cached within the SDK) +}IMV_SParamUpdateArg; + +/// \~chinese +/// \brief 流事件信息 +/// \~english +/// \brief Stream event information +typedef struct _IMV_SStreamArg +{ + unsigned int channel; ///< \~chinese 流通道号 \~english Channel no. + uint64_t blockId; ///< \~chinese 流数据BlockID \~english Block ID of stream data + uint64_t timeStamp; ///< \~chinese 时间戳 \~english Event time stamp + IMV_EEventStatus eStreamEventStatus; ///< \~chinese 流事件状态码 \~english Stream event status code + unsigned int status; ///< \~chinese 事件状态错误码 \~english Status error code + unsigned int nReserve[9]; ///< \~chinese 预留字段 \~english Reserved field +}IMV_SStreamArg; + +/// \~chinese +/// 消息通道事件ID列表 +/// \~english +/// message channel event id list +#define IMV_MSG_EVENT_ID_EXPOSURE_END 0x9001 +#define IMV_MSG_EVENT_ID_FRAME_TRIGGER 0x9002 +#define IMV_MSG_EVENT_ID_FRAME_START 0x9003 +#define IMV_MSG_EVENT_ID_ACQ_START 0x9004 +#define IMV_MSG_EVENT_ID_ACQ_TRIGGER 0x9005 +#define IMV_MSG_EVENT_ID_DATA_READ_OUT 0x9006 + +/// \~chinese +/// \brief 消息通道事件信息 +/// \~english +/// \brief Message channel event information +typedef struct _IMV_SMsgChannelArg +{ + unsigned short eventId; ///< \~chinese 事件Id \~english Event id + unsigned short channelId; ///< \~chinese 消息通道号 \~english Channel id + uint64_t blockId; ///< \~chinese 流数据BlockID \~english Block ID of stream data + uint64_t timeStamp; ///< \~chinese 时间戳 \~english Event timestamp + unsigned int nReserve[8]; ///< \~chinese 预留字段 \~english Reserved field + unsigned int nParamCnt; ///< \~chinese 参数个数 \~english The number of parameters which need update + IMV_String* pParamNameList; ///< \~chinese 事件相关的属性名列集合(SDK内部缓存) \~english Array of parameter's name which is related(cached within the SDK) +}IMV_SMsgChannelArg; + +/// \~chinese +/// \brief Chunk数据信息 +/// \~english +/// \brief Chunk data information +typedef struct _IMV_ChunkDataInfo +{ + unsigned int chunkID; ///< \~chinese ChunkID \~english ChunkID + unsigned int nParamCnt; ///< \~chinese 属性名个数 \~english The number of paramNames + IMV_String* pParamNameList; ///< \~chinese Chunk数据对应的属性名集合(SDK内部缓存) \~english ParamNames Corresponding property name of chunk data(cached within the SDK) +}IMV_ChunkDataInfo; + +/// \~chinese +/// \brief 帧图像信息 +/// \~english +/// \brief The frame image information +typedef struct _IMV_FrameInfo +{ + uint64_t blockId; ///< \~chinese 帧Id(仅对GigE/Usb/PCIe相机有效) \~english The block ID(GigE/Usb/PCIe camera only) + unsigned int status; ///< \~chinese 数据帧状态(0是正常状态) \~english The status of frame(0 is normal status) + unsigned int width; ///< \~chinese 图像宽度 \~english The width of image + unsigned int height; ///< \~chinese 图像高度 \~english The height of image + unsigned int size; ///< \~chinese 图像大小 \~english The size of image + IMV_EPixelType pixelFormat; ///< \~chinese 图像像素格式 \~english The pixel format of image + uint64_t timeStamp; ///< \~chinese 图像时间戳(仅对GigE/Usb/PCIe相机有效) \~english The timestamp of image(GigE/Usb/PCIe camera only) + unsigned int chunkCount; ///< \~chinese 帧数据中包含的Chunk个数(仅对GigE/Usb相机有效) \~english The number of chunk in frame data(GigE/Usb Camera Only) + unsigned int paddingX; ///< \~chinese 图像paddingX(仅对GigE/Usb/PCIe相机有效) \~english The paddingX of image(GigE/Usb/PCIe camera only) + unsigned int paddingY; ///< \~chinese 图像paddingY(仅对GigE/Usb/PCIe相机有效) \~english The paddingY of image(GigE/Usb/PCIe camera only) + unsigned int recvFrameTime; ///< \~chinese 图像在网络传输所用的时间(单位:微秒,非GigE相机该值为0) \~english The time taken for the image to be transmitted over the network(unit:us, The value is 0 for non-GigE camera) + unsigned int nReserved[19]; ///< \~chinese 预留字段 \~english Reserved field +}IMV_FrameInfo; + +/// \~chinese +/// \brief 帧图像数据信息 +/// \~english +/// \brief Frame image data information +typedef struct _IMV_Frame +{ + IMV_FRAME_HANDLE frameHandle; ///< \~chinese 帧图像句柄(SDK内部帧管理用) \~english Frame image handle(used for managing frame within the SDK) + unsigned char* pData; ///< \~chinese 帧图像数据的内存首地址 \~english The starting address of memory of image data + IMV_FrameInfo frameInfo; ///< \~chinese 帧信息 \~english Frame information + unsigned int nReserved[10]; ///< \~chinese 预留字段 \~english Reserved field +}IMV_Frame; + +/// \~chinese +/// \brief PCIE设备统计流信息 +/// \~english +/// \brief PCIE device stream statistics information +typedef struct _IMV_PCIEStreamStatsInfo +{ + unsigned int imageError; ///< \~chinese 图像错误的帧数 \~english Number of images error frames + unsigned int lostPacketBlock; ///< \~chinese 丢包的帧数 \~english Number of frames lost + unsigned int nReserved0[10]; ///< \~chinese 预留 \~english Reserved field + + unsigned int imageReceived; ///< \~chinese 正常获取的帧数 \~english Number of frames acquired + double fps; ///< \~chinese 帧率 \~english Frame rate + double bandwidth; ///< \~chinese 带宽(Mbps) \~english Bandwidth(Mbps) + unsigned int nReserved[8]; ///< \~chinese 预留 \~english Reserved field +}IMV_PCIEStreamStatsInfo; + +/// \~chinese +/// \brief U3V设备统计流信息 +/// \~english +/// \brief U3V device stream statistics information +typedef struct _IMV_U3VStreamStatsInfo +{ + unsigned int imageError; ///< \~chinese 图像错误的帧数 \~english Number of images error frames + unsigned int lostPacketBlock; ///< \~chinese 丢包的帧数 \~english Number of frames lost + unsigned int nReserved0[10]; ///< \~chinese 预留 \~english Reserved field + + unsigned int imageReceived; ///< \~chinese 正常获取的帧数 \~english Number of images error frames + double fps; ///< \~chinese 帧率 \~english Frame rate + double bandwidth; ///< \~chinese 带宽(Mbps) \~english Bandwidth(Mbps) + unsigned int nReserved[8]; ///< \~chinese 预留 \~english Reserved field +}IMV_U3VStreamStatsInfo; + +/// \~chinese +/// \brief Gige设备统计流信息 +/// \~english +/// \brief Gige device stream statistics information +typedef struct _IMV_GigEStreamStatsInfo +{ + unsigned int nReserved0[10]; ///< \~chinese 预留 \~english Reserved field + + unsigned int imageError; ///< \~chinese 图像错误的帧数 \~english Number of image error frames + unsigned int lostPacketBlock; ///< \~chinese 丢包的帧数 \~english Number of frames lost + unsigned int nReserved1[4]; ///< \~chinese 预留 \~english Reserved field + unsigned int nReserved2[5]; ///< \~chinese 预留 \~english Reserved field + + unsigned int imageReceived; ///< \~chinese 正常获取的帧数 \~english Number of frames acquired + double fps; ///< \~chinese 帧率 \~english Frame rate + double bandwidth; ///< \~chinese 带宽(Mbps) \~english Bandwidth(Mbps) + unsigned int nReserved[4]; ///< \~chinese 预留 \~english Reserved field +}IMV_GigEStreamStatsInfo; + +/// \~chinese +/// \brief 统计流信息 +/// \~english +/// \brief Stream statistics information +typedef struct _IMV_StreamStatisticsInfo +{ + IMV_ECameraType nCameraType; ///< \~chinese 设备类型 \~english Device type + + union + { + IMV_PCIEStreamStatsInfo pcieStatisticsInfo; ///< \~chinese PCIE设备统计信息 \~english PCIE device statistics information + IMV_U3VStreamStatsInfo u3vStatisticsInfo; ///< \~chinese U3V设备统计信息 \~english U3V device statistics information + IMV_GigEStreamStatsInfo gigeStatisticsInfo; ///< \~chinese Gige设备统计信息 \~english GIGE device statistics information + }; +}IMV_StreamStatisticsInfo; + +/// \~chinese +/// \brief 枚举属性的枚举值信息 +/// \~english +/// \brief Enumeration property 's enumeration value information +typedef struct _IMV_EnumEntryInfo +{ + uint64_t value; ///< \~chinese 枚举值 \~english Enumeration value + char name[IMV_MAX_STRING_LENTH]; ///< \~chinese symbol名 \~english Symbol name +}IMV_EnumEntryInfo; + +/// \~chinese +/// \brief 枚举属性的可设枚举值列表信息 +/// \~english +/// \brief Enumeration property 's settable enumeration value list information +typedef struct _IMV_EnumEntryList +{ + unsigned int nEnumEntryBufferSize; ///< \~chinese 存放枚举值内存大小 \~english The size of saving enumeration value + IMV_EnumEntryInfo* pEnumEntryInfo; ///< \~chinese 存放可设枚举值列表(调用者分配缓存) \~english Save the list of settable enumeration value(allocated cache by the caller) +}IMV_EnumEntryList; + +/// \~chinese +/// \brief 像素转换结构体 +/// \~english +/// \brief Pixel convert structure +typedef struct _IMV_PixelConvertParam +{ + unsigned int nWidth; ///< [IN] \~chinese 图像宽 \~english Width + unsigned int nHeight; ///< [IN] \~chinese 图像高 \~english Height + IMV_EPixelType ePixelFormat; ///< [IN] \~chinese 像素格式 \~english Pixel format + unsigned char* pSrcData; ///< [IN] \~chinese 输入图像数据 \~english Input image data + unsigned int nSrcDataLen; ///< [IN] \~chinese 输入图像长度 \~english Input image length + unsigned int nPaddingX; ///< [IN] \~chinese 图像宽填充 \~english Padding X + unsigned int nPaddingY; ///< [IN] \~chinese 图像高填充 \~english Padding Y + IMV_EBayerDemosaic eBayerDemosaic; ///< [IN] \~chinese 转换Bayer格式算法 \~english Alorithm used for Bayer demosaic + IMV_EPixelType eDstPixelFormat; ///< [IN] \~chinese 目标像素格式 \~english Destination pixel format + unsigned char* pDstBuf; ///< [OUT] \~chinese 输出数据缓存(调用者分配缓存) \~english Output data buffer(allocated cache by the caller) + unsigned int nDstBufSize; ///< [IN] \~chinese 提供的输出缓冲区大小 \~english Provided output buffer size + unsigned int nDstDataLen; ///< [OUT] \~chinese 输出数据长度 \~english Output data length + unsigned int nReserved[8]; ///< \~chinese 预留 \~english Reserved field +}IMV_PixelConvertParam; + +/// \~chinese +/// \brief 录像结构体 +/// \~english +/// \brief Record structure +typedef struct _IMV_RecordParam +{ + unsigned int nWidth; ///< [IN] \~chinese 图像宽 \~english Width + unsigned int nHeight; ///< [IN] \~chinese 图像高 \~english Height + float fFameRate; ///< [IN] \~chinese 帧率(大于0) \~english Frame rate(greater than 0) + unsigned int nQuality; ///< [IN] \~chinese 视频质量(1-100) \~english Video quality(1-100) + IMV_EVideoType recordFormat; ///< [IN] \~chinese 视频格式 \~english Video format + const char* pRecordFilePath; ///< [IN] \~chinese 保存视频路径 \~english Save video path + unsigned int nReserved[5]; ///< \~chinese 预留 \~english Reserved +}IMV_RecordParam; + +/// \~chinese +/// \brief 录像用帧信息结构体 +/// \~english +/// \brief Frame information for recording structure +typedef struct _IMV_RecordFrameInfoParam +{ + unsigned char* pData; ///< [IN] \~chinese 图像数据 \~english Image data + unsigned int nDataLen; ///< [IN] \~chinese 图像数据长度 \~english Image data length + unsigned int nPaddingX; ///< [IN] \~chinese 图像宽填充 \~english Padding X + unsigned int nPaddingY; ///< [IN] \~chinese 图像高填充 \~english Padding Y + IMV_EPixelType ePixelFormat; ///< [IN] \~chinese 像素格式 \~english Pixel format + unsigned int nReserved[5]; ///< \~chinese 预留 \~english Reserved +}IMV_RecordFrameInfoParam; + +/// \~chinese +/// \brief 图像翻转结构体 +/// \~english +/// \brief Flip image structure +typedef struct _IMV_FlipImageParam +{ + unsigned int nWidth; ///< [IN] \~chinese 图像宽 \~english Width + unsigned int nHeight; ///< [IN] \~chinese 图像高 \~english Height + IMV_EPixelType ePixelFormat; ///< [IN] \~chinese 像素格式 \~english Pixel format + IMV_EFlipType eFlipType; ///< [IN] \~chinese 翻转类型 \~english Flip type + unsigned char* pSrcData; ///< [IN] \~chinese 输入图像数据 \~english Input image data + unsigned int nSrcDataLen; ///< [IN] \~chinese 输入图像长度 \~english Input image length + unsigned char* pDstBuf; ///< [OUT] \~chinese 输出数据缓存(调用者分配缓存) \~english Output data buffer(allocated cache by the caller) + unsigned int nDstBufSize; ///< [IN] \~chinese 提供的输出缓冲区大小 \~english Provided output buffer size + unsigned int nDstDataLen; ///< [OUT] \~chinese 输出数据长度 \~english Output data length + unsigned int nReserved[8]; ///< \~chinese 预留 \~english Reserved +}IMV_FlipImageParam; + +/// \~chinese +/// \brief 图像旋转结构体 +/// \~english +/// \brief Rotate image structure +typedef struct _IMV_RotateImageParam +{ + unsigned int nWidth; ///< [IN][OUT] \~chinese 图像宽 \~english Width + unsigned int nHeight; ///< [IN][OUT] \~chinese 图像高 \~english Height + IMV_EPixelType ePixelFormat; ///< [IN] \~chinese 像素格式 \~english Pixel format + IMV_ERotationAngle eRotationAngle; ///< [IN] \~chinese 旋转角度 \~english Rotation angle + unsigned char* pSrcData; ///< [IN] \~chinese 输入图像数据 \~english Input image data + unsigned int nSrcDataLen; ///< [IN] \~chinese 输入图像长度 \~english Input image length + unsigned char* pDstBuf; ///< [OUT] \~chinese 输出数据缓存(调用者分配缓存) \~english Output data buffer(allocated cache by the caller) + unsigned int nDstBufSize; ///< [IN] \~chinese 提供的输出缓冲区大小 \~english Provided output buffer size + unsigned int nDstDataLen; ///< [OUT] \~chinese 输出数据长度 \~english Output data length + unsigned int nReserved[8]; ///< \~chinese 预留 \~english Reserved +}IMV_RotateImageParam; + +/// \~chinese +/// \brief 设备连接状态事件回调函数声明 +/// \param pParamUpdateArg [in] 回调时主动推送的设备连接状态事件信息 +/// \param pUser [in] 用户自定义数据 +/// \~english +/// \brief Call back function declaration of device connection status event +/// \param pStreamArg [in] The device connection status event which will be active pushed out during the callback +/// \param pUser [in] User defined data +typedef void(*IMV_ConnectCallBack)(const IMV_SConnectArg* pConnectArg, void* pUser); + +/// \~chinese +/// \brief 参数更新事件回调函数声明 +/// \param pParamUpdateArg [in] 回调时主动推送的参数更新事件信息 +/// \param pUser [in] 用户自定义数据 +/// \~english +/// \brief Call back function declaration of parameter update event +/// \param pStreamArg [in] The parameter update event which will be active pushed out during the callback +/// \param pUser [in] User defined data +typedef void(*IMV_ParamUpdateCallBack)(const IMV_SParamUpdateArg* pParamUpdateArg, void* pUser); + +/// \~chinese +/// \brief 流事件回调函数声明 +/// \param pStreamArg [in] 回调时主动推送的流事件信息 +/// \param pUser [in] 用户自定义数据 +/// \~english +/// \brief Call back function declaration of stream event +/// \param pStreamArg [in] The stream event which will be active pushed out during the callback +/// \param pUser [in] User defined data +typedef void(*IMV_StreamCallBack)(const IMV_SStreamArg* pStreamArg, void* pUser); + +/// \~chinese +/// \brief 消息通道事件回调函数声明 +/// \param pMsgChannelArg [in] 回调时主动推送的消息通道事件信息 +/// \param pUser [in] 用户自定义数据 +/// \~english +/// \brief Call back function declaration of message channel event +/// \param pMsgChannelArg [in] The message channel event which will be active pushed out during the callback +/// \param pUser [in] User defined data +typedef void(*IMV_MsgChannelCallBack)(const IMV_SMsgChannelArg* pMsgChannelArg, void* pUser); + +/// \~chinese +/// \brief 帧数据信息回调函数声明 +/// \param pFrame [in] 回调时主动推送的帧信息 +/// \param pUser [in] 用户自定义数据 +/// \~english +/// \brief Call back function declaration of frame data information +/// \param pFrame [in] The frame information which will be active pushed out during the callback +/// \param pUser [in] User defined data +typedef void(*IMV_FrameCallBack)(IMV_Frame* pFrame, void* pUser); + +#endif // __IMV_DEFINES_H__ \ No newline at end of file diff --git a/camera_driver/include/IMVApi.h b/camera_driver/include/IMVApi.h new file mode 100644 index 0000000..af056da --- /dev/null +++ b/camera_driver/include/IMVApi.h @@ -0,0 +1,1071 @@ +/// \mainpage +/// \~chinese +/// \htmlinclude mainpage_chs.html +/// \~english +/// \htmlinclude mainpage_eng.html + +#ifndef __IMV_API_H__ +#define __IMV_API_H__ + +#include "IMVDefines.h" + +/// \~chinese +/// \brief 动态库导入导出定义 +/// \~english +/// \brief Dynamic library import and export definition +#if (defined (_WIN32) || defined(WIN64)) + #ifdef IMV_API_DLL_BUILD + #define IMV_API _declspec(dllexport) + #else + #define IMV_API _declspec(dllimport) + #endif + + #define IMV_CALL __stdcall +#else + #define IMV_API + #define IMV_CALL +#endif + +#ifdef __cplusplus +extern "C" { +#endif + +/// \~chinese +/// \brief 获取版本信息 +/// \return 成功时返回版本信息,失败时返回NULL +/// \~english +/// \brief get version information +/// \return Success, return version info. Failure, return NULL +IMV_API const char* IMV_CALL IMV_GetVersion(void); + +/// \~chinese +/// \brief 枚举设备 +/// \param pDeviceList [OUT] 设备列表 +/// \param interfaceType [IN] 待枚举的接口类型, 类型可任意组合,如 interfaceTypeGige | interfaceTypeUsb3 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 1、当interfaceType = interfaceTypeAll 时,枚举所有接口下的在线设备\n +/// 2、当interfaceType = interfaceTypeGige 时,枚举所有GigE网口下的在线设备\n +/// 3、当interfaceType = interfaceTypeUsb3 时,枚举所有USB接口下的在线设备\n +/// 4、当interfaceType = interfaceTypeCL 时,枚举所有CameraLink接口下的在线设备\n +/// 5、该接口下的interfaceType支持任意接口类型的组合,如,若枚举所有GigE网口和USB3接口下的在线设备时, +/// 可将interfaceType设置为 interfaceType = interfaceTypeGige | interfaceTypeUsb3,其它接口类型组合以此类推 +/// \~english +/// \brief Enumerate Device +/// \param pDeviceList [OUT] Device list +/// \param interfaceType [IN] The interface type you want to find, support any interface type combination, sucn as interfaceTypeGige | interfaceTypeUsb3 +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// 1、when interfaceType = interfaceTypeAll, enumerate devices in all interface types\n +/// 2、when interfaceType = interfaceTypeGige, enumerate devices in GigE interface \n +/// 3、when interfaceType = interfaceTypeUsb3, enumerate devices in USB interface\n +/// 4、when interfaceType = interfaceTypeCL, enumerate devices in CameraLink interface\n +/// 5、interfaceType supports any interface type combination. For example, if you want to find all GigE and USB3 devices, +/// you can set interfaceType as interfaceType = interfaceTypeGige | interfaceTypeUsb3. +IMV_API int IMV_CALL IMV_EnumDevices(OUT IMV_DeviceList *pDeviceList, IN unsigned int interfaceType); + +/// \~chinese +/// \brief 以单播形式枚举设备, 仅限Gige设备使用 +/// \param pDeviceList [OUT] 设备列表 +/// \param pIpAddress [IN] 设备的IP地址 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Enumerate device by unicast mode. Only for Gige device. +/// \param pDeviceList [OUT] Device list +/// \param pIpAddress [IN] IP address of the device +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_EnumDevicesByUnicast(OUT IMV_DeviceList *pDeviceList, IN const char* pIpAddress); + +/// \~chinese +/// \brief 通过指定标示符创建设备句柄,如指定索引、设备键、设备自定义名、IP地址 +/// \param handle [OUT] 设备句柄 +/// \param mode [IN] 创建设备方式 +/// \param pIdentifier [IN] 指定标示符(设备键、设备自定义名、IP地址为char类型指针强转void类型指针,索引为unsigned int类型指针强转void类型指针) +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Create device handle by specifying identifiers, such as specifying index, device key, device userID, and IP address +/// \param handle [OUT] Device handle +/// \param mode [IN] Create handle mode +/// \param pIdentifier [IN] Specifying identifiers(device key, device userID, and IP address is char* forced to void*, index is unsigned int* forced to void*) +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_CreateHandle(OUT IMV_HANDLE* handle, IN IMV_ECreateHandleMode mode, IN void* pIdentifier); + +/// \~chinese +/// \brief 销毁设备句柄 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Destroy device handle +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_DestroyHandle(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 获取设备信息 +/// \param handle [IN] 设备句柄 +/// \param pDevInfo [OUT] 设备信息 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get device information +/// \param handle [IN] Device handle +/// \param pDevInfo [OUT] Device information +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetDeviceInfo(IN IMV_HANDLE handle, OUT IMV_DeviceInfo *pDevInfo); + +/// \~chinese +/// \brief 打开设备 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Open Device +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_Open(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 打开设备 +/// \param handle [IN] 设备句柄 +/// \param accessPermission [IN] 控制通道权限(IMV_Open默认使用accessPermissionControl权限) +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Open Device +/// \param handle [IN] Device handle +/// \param accessPermission [IN] Control access permission(Default used accessPermissionControl in IMV_Open) +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_OpenEx(IN IMV_HANDLE handle, IN IMV_ECameraAccessPermission accessPermission); + +/// \~chinese +/// \brief 判断设备是否已打开 +/// \param handle [IN] 设备句柄 +/// \return 打开状态,返回true;关闭状态或者掉线状态,返回false +/// \~english +/// \brief Check whether device is opened or not +/// \param handle [IN] Device handle +/// \return Opened, return true. Closed or Offline, return false +IMV_API bool IMV_CALL IMV_IsOpen(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 关闭设备 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Close Device +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_Close(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 修改设备IP, 仅限Gige设备使用 +/// \param handle [IN] 设备句柄 +/// \param pIpAddress [IN] IP地址 +/// \param pSubnetMask [IN] 子网掩码 +/// \param pGateway [IN] 默认网关 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 1、调用该函数时如果pSubnetMask和pGateway都设置了有效值,则以此有效值为准;\n +/// 2、调用该函数时如果pSubnetMask和pGateway都设置了NULL,则内部实现时用它所连接网卡的子网掩码和网关代替\n +/// 3、调用该函数时如果pSubnetMask和pGateway两者中其中一个为NULL,另一个非NULL,则返回错误 +/// \~english +/// \brief Modify device IP. Only for Gige device. +/// \param handle [IN] Device handle +/// \param pIpAddress [IN] IP address +/// \param pSubnetMask [IN] SubnetMask +/// \param pGateway [IN] Gateway +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// 1、When callback this function, if the values of pSubnetMask and pGateway are both valid then we consider the value is correct\n +/// 2、When callback this function, if the values of pSubnetMask and pGateway are both NULL, +/// then these values will be replaced by the subnetmask and gateway of NIC which this device connect to.\n +/// 3、When callback this function, if there is one value of pSubnetMask or pGateway is NULL and the other one is not NULL, then return error +IMV_API int IMV_CALL IMV_GIGE_ForceIpAddress(IN IMV_HANDLE handle, IN const char* pIpAddress, IN const char* pSubnetMask, IN const char* pGateway); + +/// \~chinese +/// \brief 获取设备的当前访问权限, 仅限Gige设备使用 +/// \param handle [IN] 设备句柄 +/// \param pAccessPermission [OUT] 设备的当前访问权限 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get current access permission of device. Only for Gige device. +/// \param handle [IN] Device handle +/// \param pAccessPermission [OUT] Current access permission of device +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GIGE_GetAccessPermission(IN IMV_HANDLE handle, OUT IMV_ECameraAccessPermission* pAccessPermission); + +/// \~chinese +/// \brief 设置设备对sdk命令的响应超时时间,仅限Gige设备使用 +/// \param handle [IN] 设备句柄 +/// \param timeout [IN] 超时时间,单位ms +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set the response timeout interval of device sends command to the API. Only for Gige device. +/// \param handle [IN] Device handle +/// \param timeout [IN] time out, unit:ms +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GIGE_SetAnswerTimeout(IN IMV_HANDLE handle, IN unsigned int timeout); + +/// \~chinese +/// \brief 下载设备描述XML文件,并保存到指定路径,如:D:\\xml.zip +/// \param handle [IN] 设备句柄 +/// \param pFullFileName [IN] 文件要保存的路径 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Download device description XML file, and save the files to specified path. e.g. D:\\xml.zip +/// \param handle [IN] Device handle +/// \param pFullFileName [IN] The full paths where the downloaded XMl files would be saved to +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_DownLoadGenICamXML(IN IMV_HANDLE handle, IN const char* pFullFileName); + +/// \~chinese +/// \brief 保存设备配置到指定的位置。同名文件已存在时,覆盖。 +/// \param handle [IN] 设备句柄 +/// \param pFullFileName [IN] 导出的设备配置文件全名(含路径),如:D:\\config.xml 或 D:\\config.mvcfg +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Save the configuration of the device. Overwrite the file if exists. +/// \param handle [IN] Device handle +/// \param pFullFileName [IN] The full path name of the property file(xml). e.g. D:\\config.xml or D:\\config.mvcfg +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SaveDeviceCfg(IN IMV_HANDLE handle, IN const char* pFullFileName); + +/// \~chinese +/// \brief 从文件加载设备xml配置 +/// \param handle [IN] 设备句柄 +/// \param pFullFileName [IN] 设备配置(xml)文件全名(含路径),如:D:\\config.xml 或 D:\\config.mvcfg +/// \param pErrorList [OUT] 加载失败的属性名列表。存放加载失败的属性上限为IMV_MAX_ERROR_LIST_NUM。 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief load the configuration of the device +/// \param handle [IN] Device handle +/// \param pFullFileName [IN] The full path name of the property file(xml). e.g. D:\\config.xml or D:\\config.mvcfg +/// \param pErrorList [OUT] The list of load failed properties. The failed to load properties list up to IMV_MAX_ERROR_LIST_NUM. +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_LoadDeviceCfg(IN IMV_HANDLE handle, IN const char* pFullFileName, OUT IMV_ErrorList* pErrorList); + +/// \~chinese +/// \brief 写用户自定义数据。相机内部保留32768字节用于用户存储自定义数据(此功能针对本品牌相机,其它品牌相机无此功能) +/// \param handle [IN] 设备句柄 +/// \param pBuffer [IN] 数据缓冲的指针 +/// \param pLength [IN] 期望写入的字节数 [OUT] 实际写入的字节数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Write user-defined data; Inside the camera, there are 32768 bytes reserved for user to store private data (Only for our own camera has this function) +/// \param handle [IN] Device handle +/// \param pBuffer [IN] Pointer of the data buffer +/// \param pLength [IN] Byte count written expected [OUT] Byte count written in fact +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_WriteUserPrivateData(IN IMV_HANDLE handle, IN void* pBuffer, IN_OUT unsigned int* pLength); + +/// \~chinese +/// \brief 读用户自定义数据。相机内部保留32768字节用于用户存储自定义数据(此功能针对本品牌相机,其它品牌相机无此功能) +/// \param handle [IN] 设备句柄 +/// \param pBuffer [OUT] 数据缓冲的指针 +/// \param pLength [IN] 期望读出的字节数 [OUT] 实际读出的字节数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Read user-defined data; Inside the camera, there are 32768 bytes reserved for user to store private data (Only for our own camera has this function) +/// \param handle [IN] Device handle +/// \param pBuffer [OUT] Pointer of the data buffer +/// \param pLength [IN] Byte count read expected [OUT] Byte count read in fact +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ReadUserPrivateData(IN IMV_HANDLE handle, OUT void* pBuffer, IN_OUT unsigned int* pLength); + +/// \~chinese +/// \brief 往相机串口寄存器写数据,每次写会清除掉上次的数据(此功能只支持包含串口功能的本品牌相机) +/// \param handle [IN] 设备句柄 +/// \param pBuffer [IN] 数据缓冲的指针 +/// \param pLength [IN] 期望写入的字节数 [OUT] 实际写入的字节数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Write serial data to camera serial register, will erase the data writen before (Only for our own camera with serial port has this function) +/// \param handle [IN] Device handle +/// \param pBuffer [IN] Pointer of the data buffer +/// \param pLength [IN] Byte count written expected [OUT] Byte count written in fact +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_WriteUARTData(IN IMV_HANDLE handle, IN void* pBuffer, IN_OUT unsigned int* pLength); + +/// \~chinese +/// \brief 从相机串口寄存器读取串口数据(此功能只支持包含串口功能的本品牌相机 ) +/// \param handle [IN] 设备句柄 +/// \param pBuffer [OUT] 数据缓冲的指针 +/// \param pLength [IN] 期望读出的字节数 [OUT] 实际读出的字节数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Read serial data from camera serial register (Only for our own camera with serial port has this function) +/// \param handle [IN] Device handle +/// \param pBuffer [OUT] Pointer of the data buffer +/// \param pLength [IN] Byte count read expected [OUT] Byte count read in fact +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ReadUARTData(IN IMV_HANDLE handle, OUT void* pBuffer, IN_OUT unsigned int* pLength); + +/// \~chinese +/// \brief 设备连接状态事件回调注册 +/// \param handle [IN] 设备句柄 +/// \param proc [IN] 设备连接状态事件回调函数 +/// \param pUser [IN] 用户自定义数据, 可设为NULL +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持一个回调函数,且设备关闭后,注册会失效,打开设备后需重新注册 +/// \~english +/// \brief Register call back function of device connection status event. +/// \param handle [IN] Device handle +/// \param proc [IN] Call back function of device connection status event +/// \param pUser [IN] User defined data,It can be set to NULL +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only one call back function is supported.\n +/// Registration becomes invalid after the device is closed, , and need to re-register after the device is opened +IMV_API int IMV_CALL IMV_SubscribeConnectArg(IN IMV_HANDLE handle, IN IMV_ConnectCallBack proc, IN void* pUser); + +/// \~chinese +/// \brief 参数更新事件回调注册 +/// \param handle [IN] 设备句柄 +/// \param proc [IN] 参数更新注册的事件回调函数 +/// \param pUser [IN] 用户自定义数据, 可设为NULL +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持一个回调函数,且设备关闭后,注册会失效,打开设备后需重新注册 +/// \~english +/// \brief Register call back function of parameter update event. +/// \param handle [IN] Device handle +/// \param proc [IN] Call back function of parameter update event +/// \param pUser [IN] User defined data,It can be set to NULL +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only one call back function is supported.\n +/// Registration becomes invalid after the device is closed, , and need to re-register after the device is opened +IMV_API int IMV_CALL IMV_SubscribeParamUpdateArg(IN IMV_HANDLE handle, IN IMV_ParamUpdateCallBack proc, IN void* pUser); + +/// \~chinese +/// \brief 流通道事件回调注册 +/// \param handle [IN] 设备句柄 +/// \param proc [IN] 流通道事件回调注册函数 +/// \param pUser [IN] 用户自定义数据, 可设为NULL +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持一个回调函数,且设备关闭后,注册会失效,打开设备后需重新注册 +/// \~english +/// \brief Register call back function of stream channel event. +/// \param handle [IN] Device handle +/// \param proc [IN] Call back function of stream channel event +/// \param pUser [IN] User defined data,It can be set to NULL +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only one call back function is supported.\n +/// Registration becomes invalid after the device is closed, , and need to re-register after the device is opened +IMV_API int IMV_CALL IMV_SubscribeStreamArg(IN IMV_HANDLE handle, IN IMV_StreamCallBack proc, IN void* pUser); + +/// \~chinese +/// \brief 消息通道事件回调注册 +/// \param handle [IN] 设备句柄 +/// \param proc [IN] 消息通道事件回调注册函数 +/// \param pUser [IN] 用户自定义数据, 可设为NULL +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持一个回调函数,且设备关闭后,注册会失效,打开设备后需重新注册 +/// \~english +/// \brief Register call back function of message channel event. +/// \param handle [IN] Device handle +/// \param proc [IN] Call back function of message channel event +/// \param pUser [IN] User defined data,It can be set to NULL +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only one call back function is supported.\n +/// Registration becomes invalid after the device is closed, , and need to re-register after the device is opened +IMV_API int IMV_CALL IMV_SubscribeMsgChannelArg(IN IMV_HANDLE handle, IN IMV_MsgChannelCallBack proc, IN void* pUser); + +/// \~chinese +/// \brief 设置帧数据缓存个数 +/// \param handle [IN] 设备句柄 +/// \param nSize [IN] 缓存数量 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 不能在拉流过程中设置 +/// \~english +/// \brief Set frame buffer count +/// \param handle [IN] Device handle +/// \param nSize [IN] The buffer count +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// It can not be set during frame grabbing +IMV_API int IMV_CALL IMV_SetBufferCount(IN IMV_HANDLE handle, IN unsigned int nSize); + +/// \~chinese +/// \brief 清除帧数据缓存 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Clear frame buffer +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ClearFrameBuffer(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 设置驱动包间隔时间(MS),仅对Gige设备有效 +/// \param handle [IN] 设备句柄 +/// \param nTimeout [IN] 包间隔时间,单位是毫秒 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 触发模式尾包丢失重传机制 +/// \~english +/// \brief Set packet timeout(MS), only for Gige device +/// \param handle [IN] Device handle +/// \param nTimeout [IN] Time out value, unit is MS +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// The resend mechanism of tail packet loss on trigger mode +IMV_API int IMV_CALL IMV_GIGE_SetInterPacketTimeout(IN IMV_HANDLE handle, IN unsigned int nTimeout); + +/// \~chinese +/// \brief 设置单次重传最大包个数, 仅对GigE设备有效 +/// \param handle [IN] 设备句柄 +/// \param maxPacketNum [IN] 单次重传最大包个数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// maxPacketNum为0时,该功能无效 +/// \~english +/// \brief Set the single resend maximum packet number, only for Gige device +/// \param handle [IN] Device handle +/// \param maxPacketNum [IN] The value of single resend maximum packet number +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Disable the function when maxPacketNum is 0 +IMV_API int IMV_CALL IMV_GIGE_SetSingleResendMaxPacketNum(IN IMV_HANDLE handle, IN unsigned int maxPacketNum); + +/// \~chinese +/// \brief 设置同一帧最大丢包的数量,仅对GigE设备有效 +/// \param handle [IN] 设备句柄 +/// \param maxLostPacketNum [IN] 最大丢包的数量 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// maxLostPacketNum为0时,该功能无效 +/// \~english +/// \brief Set the maximum lost packet number, only for Gige device +/// \param handle [IN] Device handle +/// \param maxLostPacketNum [IN] The value of maximum lost packet number +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Disable the function when maxLostPacketNum is 0 +IMV_API int IMV_CALL IMV_GIGE_SetMaxLostPacketNum(IN IMV_HANDLE handle, IN unsigned int maxLostPacketNum); + +/// \~chinese +/// \brief 设置U3V设备的传输数据块的数量和大小,仅对USB设备有效 +/// \param handle [IN] 设备句柄 +/// \param nNum [IN] 传输数据块的数量(范围:5-256) +/// \param nSize [IN] 传输数据块的大小(范围:8-512, 单位:KByte) +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 1、该接口暂时只有在Linux平台且使用无驱的情况下设置才有效,其他情况下返回IMV_NOT_SUPPORT错误码\n +/// 2、传输数据块数量,范围5 - 256, 默认为64,高分辨率高帧率时可以适当增加该值;多台相机共同使用时,可以适当减小该值\n +/// 3、传输每个数据块大小,范围8 - 512, 默认为64,单位是KByte +/// \~english +/// \brief Set the number and size of urb transmitted, only for USB device +/// \param handle [IN] Device handle +/// \param nNum [IN] The number of urb transmitted(range:5-256) +/// \param nSize [IN] The size of urb transmitted(range:8-512, unit:KByte) +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// 1、The interface is only supported on the Linux platform without USB driver. In other cases, it returns IMV_NOT_SUPPORT error code.\n +/// 2、The number of urb transmitted, the range is 5 - 256, and the default is 64. when high pixel and high frame rate can be appropriately increased.; +/// when multiple cameras are used together, the value can be appropriately reduced.\n +/// 3、The size of each urb transmitted, the range is 8 - 512, the default is 64, the unit is KByte. +IMV_API int IMV_CALL IMV_USB_SetUrbTransfer(IN IMV_HANDLE handle, IN unsigned int nNum, IN unsigned int nSize); + +/// \~chinese +/// \brief 开始取流 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Start grabbing +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_StartGrabbing(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 开始取流 +/// \param handle [IN] 设备句柄 +/// \param maxImagesGrabbed [IN] 允许最多的取帧数,达到指定取帧数后停止取流,如果为0,表示忽略此参数连续取流(IMV_StartGrabbing默认0) +/// \param strategy [IN] 取流策略,(IMV_StartGrabbing默认使用grabStrartegySequential策略取流) +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Start grabbing +/// \param handle [IN] Device handle +/// \param maxImagesGrabbed [IN] Maximum images allowed to grab, once it reaches the limit then stop grabbing; +/// If it is 0, then ignore this parameter and start grabbing continuously(default 0 in IMV_StartGrabbing) +/// \param strategy [IN] Image grabbing strategy; (Default grabStrartegySequential in IMV_StartGrabbing) +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_StartGrabbingEx(IN IMV_HANDLE handle, IN uint64_t maxImagesGrabbed, IN IMV_EGrabStrategy strategy); + +/// \~chinese +/// \brief 判断设备是否正在取流 +/// \param handle [IN] 设备句柄 +/// \return 正在取流,返回true;不在取流,返回false +/// \~english +/// \brief Check whether device is grabbing or not +/// \param handle [IN] Device handle +/// \return Grabbing, return true. Not grabbing, return false +IMV_API bool IMV_CALL IMV_IsGrabbing(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 停止取流 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Stop grabbing +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_StopGrabbing(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 注册帧数据回调函数(异步获取帧数据机制) +/// \param handle [IN] 设备句柄 +/// \param proc [IN] 帧数据信息回调函数,建议不要在该函数中处理耗时的操作,否则会阻塞后续帧数据的实时性 +/// \param pUser [IN] 用户自定义数据, 可设为NULL +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 该异步获取帧数据机制和同步获取帧数据机制(IMV_GetFrame)互斥,对于同一设备,系统中两者只能选其一\n +/// 只支持一个回调函数, 且设备关闭后,注册会失效,打开设备后需重新注册 +/// \~english +/// \brief Register frame data callback function( asynchronous getting frame data mechanism); +/// \param handle [IN] Device handle +/// \param proc [IN] Frame data information callback function; It is advised to not put time-cosuming operation in this function, +/// otherwise it will block follow-up data frames and affect real time performance +/// \param pUser [IN] User defined data,It can be set to NULL +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// This asynchronous getting frame data mechanism and synchronous getting frame data mechanism(IMV_GetFrame) are mutually exclusive,\n +/// only one method can be choosed between these two in system for the same device.\n +/// Only one call back function is supported.\n +/// Registration becomes invalid after the device is closed, , and need to re-register after the device is opened +IMV_API int IMV_CALL IMV_AttachGrabbing(IN IMV_HANDLE handle, IN IMV_FrameCallBack proc, IN void* pUser); + +/// \~chinese +/// \brief 获取一帧图像(同步获取帧数据机制) +/// \param handle [IN] 设备句柄 +/// \param pFrame [OUT] 帧数据信息 +/// \param timeoutMS [IN] 获取一帧图像的超时时间,INFINITE时表示无限等待,直到收到一帧数据或者停止取流。单位是毫秒 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 该接口不支持多线程调用。\n +/// 该同步获取帧机制和异步获取帧机制(IMV_AttachGrabbing)互斥,对于同一设备,系统中两者只能选其一。\n +/// 使用内部缓存获取图像,需要IMV_ReleaseFrame进行释放图像缓存。 +/// \~english +/// \brief Get a frame image(synchronous getting frame data mechanism) +/// \param handle [IN] Device handle +/// \param pFrame [OUT] Frame data information +/// \param timeoutMS [IN] The time out of getting one image, INFINITE means infinite wait until the one frame data is returned or stop grabbing.unit is MS +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// This interface does not support multi-threading.\n +/// This synchronous getting frame data mechanism and asynchronous getting frame data mechanism(IMV_AttachGrabbing) are mutually exclusive,\n +/// only one method can be chose between these two in system for the same device.\n +/// Use internal cache to get image, need to release image buffer by IMV_ReleaseFrame +IMV_API int IMV_CALL IMV_GetFrame(IN IMV_HANDLE handle, OUT IMV_Frame* pFrame, IN unsigned int timeoutMS); + +/// \~chinese +/// \brief 释放图像缓存 +/// \param handle [IN] 设备句柄 +/// \param pFrame [IN] 帧数据信息 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Free image buffer +/// \param handle [IN] Device handle +/// \param pFrame [IN] Frame image data information +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ReleaseFrame(IN IMV_HANDLE handle, IN IMV_Frame* pFrame); + +/// \~chinese +/// \brief 帧数据深拷贝克隆 +/// \param handle [IN] 设备句柄 +/// \param pFrame [IN] 克隆源帧数据信息 +/// \param pCloneFrame [OUT] 新的帧数据信息 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 使用IMV_ReleaseFrame进行释放图像缓存。 +/// \~english +/// \brief Frame data deep clone +/// \param handle [IN] Device handle +/// \param pFrame [IN] Frame data information of clone source +/// \param pCloneFrame [OUT] New frame data information +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Use IMV_ReleaseFrame to free image buffer + +IMV_API int IMV_CALL IMV_CloneFrame(IN IMV_HANDLE handle, IN IMV_Frame* pFrame, OUT IMV_Frame* pCloneFrame); + +/// \~chinese +/// \brief 获取Chunk数据(仅对GigE/Usb相机有效) +/// \param handle [IN] 设备句柄 +/// \param pFrame [IN] 帧数据信息 +/// \param index [IN] 索引ID +/// \param pChunkDataInfo [OUT] Chunk数据信息 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get chunk data(Only GigE/Usb Camera) +/// \param handle [IN] Device handle +/// \param pFrame [IN] Frame data information +/// \param index [IN] index ID +/// \param pChunkDataInfo [OUT] Chunk data infomation +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetChunkDataByIndex(IN IMV_HANDLE handle, IN IMV_Frame* pFrame, IN unsigned int index, OUT IMV_ChunkDataInfo *pChunkDataInfo); + +/// \~chinese +/// \brief 获取流统计信息(IMV_StartGrabbing / IMV_StartGrabbing执行后调用) +/// \param handle [IN] 设备句柄 +/// \param pStreamStatsInfo [OUT] 流统计信息数据 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get stream statistics infomation(Used after excuting IMV_StartGrabbing / IMV_StartGrabbing) +/// \param handle [IN] Device handle +/// \param pStreamStatsInfo [OUT] Stream statistics infomation +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetStatisticsInfo(IN IMV_HANDLE handle, OUT IMV_StreamStatisticsInfo* pStreamStatsInfo); + +/// \~chinese +/// \brief 重置流统计信息(IMV_StartGrabbing / IMV_StartGrabbing执行后调用) +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Reset stream statistics infomation(Used after excuting IMV_StartGrabbing / IMV_StartGrabbing) +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ResetStatisticsInfo(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 判断属性是否可用 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 可用,返回true;不可用,返回false +/// \~english +/// \brief Check the property is available or not +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Available, return true. Not available, return false +IMV_API bool IMV_CALL IMV_FeatureIsAvailable(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 判断属性是否可读 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 可读,返回true;不可读,返回false +/// \~english +/// \brief Check the property is readable or not +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Readable, return true. Not readable, return false +IMV_API bool IMV_CALL IMV_FeatureIsReadable(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 判断属性是否可写 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 可写,返回true;不可写,返回false +/// \~english +/// \brief Check the property is writeable or not +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Writeable, return true. Not writeable, return false +IMV_API bool IMV_CALL IMV_FeatureIsWriteable(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 判断属性是否可流 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 可流,返回true;不可流,返回false +/// \~english +/// \brief Check the property is streamable or not +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Streamable, return true. Not streamable, return false +IMV_API bool IMV_CALL IMV_FeatureIsStreamable(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 判断属性是否有效 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 有效,返回true;无效,返回false +/// \~english +/// \brief Check the property is valid or not +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Valid, return true. Invalid, return false +IMV_API bool IMV_CALL IMV_FeatureIsValid(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 获取整型属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pIntValue [OUT] 整型属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get integer property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pIntValue [OUT] Integer property value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetIntFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); + +/// \~chinese +/// \brief 获取整型属性可设的最小值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pIntValue [OUT] 整型属性可设的最小值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get the integer property settable minimum value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pIntValue [OUT] Integer property settable minimum value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetIntFeatureMin(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); + +/// \~chinese +/// \brief 获取整型属性可设的最大值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pIntValue [OUT] 整型属性可设的最大值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get the integer property settable maximum value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pIntValue [OUT] Integer property settable maximum value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetIntFeatureMax(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); + +/// \~chinese +/// \brief 获取整型属性步长 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pIntValue [OUT] 整型属性步长 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get integer property increment +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pIntValue [OUT] Integer property increment +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetIntFeatureInc(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT int64_t* pIntValue); + +/// \~chinese +/// \brief 设置整型属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param intValue [IN] 待设置的整型属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set integer property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param intValue [IN] Integer property value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetIntFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, IN int64_t intValue); + +/// \~chinese +/// \brief 获取浮点属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pDoubleValue [OUT] 浮点属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get double property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pDoubleValue [OUT] Double property value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetDoubleFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); + +/// \~chinese +/// \brief 获取浮点属性可设的最小值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pDoubleValue [OUT] 浮点属性可设的最小值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get the double property settable minimum value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pDoubleValue [OUT] Double property settable minimum value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetDoubleFeatureMin(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); + +/// \~chinese +/// \brief 获取浮点属性可设的最大值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pDoubleValue [OUT] 浮点属性可设的最大值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get the double property settable maximum value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pDoubleValue [OUT] Double property settable maximum value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetDoubleFeatureMax(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT double* pDoubleValue); + +/// \~chinese +/// \brief 设置浮点属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param doubleValue [IN] 待设置的浮点属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set double property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param doubleValue [IN] Double property value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetDoubleFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, IN double doubleValue); + +/// \~chinese +/// \brief 获取布尔属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pBoolValue [OUT] 布尔属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get boolean property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pBoolValue [OUT] Boolean property value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetBoolFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT bool* pBoolValue); + +/// \~chinese +/// \brief 设置布尔属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param boolValue [IN] 待设置的布尔属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set boolean property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param boolValue [IN] Boolean property value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetBoolFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, IN bool boolValue); + +/// \~chinese +/// \brief 获取枚举属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pEnumValue [OUT] 枚举属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get enumeration property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pEnumValue [OUT] Enumeration property value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetEnumFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT uint64_t* pEnumValue); + +/// \~chinese +/// \brief 设置枚举属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param enumValue [IN] 待设置的枚举属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set enumeration property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param enumValue [IN] Enumeration property value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetEnumFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, IN uint64_t enumValue); + +/// \~chinese +/// \brief 获取枚举属性symbol值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pEnumSymbol [OUT] 枚举属性symbol值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get enumeration property symbol value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pEnumSymbol [OUT] Enumeration property symbol value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetEnumFeatureSymbol(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT IMV_String* pEnumSymbol); + +/// \~chinese +/// \brief 设置枚举属性symbol值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pEnumSymbol [IN] 待设置的枚举属性symbol值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set enumeration property symbol value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pEnumSymbol [IN] Enumeration property symbol value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetEnumFeatureSymbol(IN IMV_HANDLE handle, IN const char* pFeatureName, IN const char* pEnumSymbol); + +/// \~chinese +/// \brief 获取枚举属性的可设枚举值的个数 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pEntryNum [OUT] 枚举属性的可设枚举值的个数 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get the number of enumeration property settable enumeration +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pEntryNum [OUT] The number of enumeration property settable enumeration value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetEnumFeatureEntryNum(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT unsigned int* pEntryNum); + +/// \~chinese +/// \brief 获取枚举属性的可设枚举值列表 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pEnumEntryList [OUT] 枚举属性的可设枚举值列表 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get settable enumeration value list of enumeration property +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pEnumEntryList [OUT] Settable enumeration value list of enumeration property +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetEnumFeatureEntrys(IN IMV_HANDLE handle, IN const char* pFeatureName, IN_OUT IMV_EnumEntryList* pEnumEntryList); + +/// \~chinese +/// \brief 获取字符串属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pStringValue [OUT] 字符串属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Get string property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pStringValue [OUT] String property value +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_GetStringFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, OUT IMV_String* pStringValue); + +/// \~chinese +/// \brief 设置字符串属性值 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \param pStringValue [IN] 待设置的字符串属性值 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Set string property value +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \param pStringValue [IN] String property value to be set +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_SetStringFeatureValue(IN IMV_HANDLE handle, IN const char* pFeatureName, IN const char* pStringValue); + +/// \~chinese +/// \brief 执行命令属性 +/// \param handle [IN] 设备句柄 +/// \param pFeatureName [IN] 属性名 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Execute command property +/// \param handle [IN] Device handle +/// \param pFeatureName [IN] Feature name +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_ExecuteCommandFeature(IN IMV_HANDLE handle, IN const char* pFeatureName); + +/// \~chinese +/// \brief 像素格式转换 +/// \param handle [IN] 设备句柄 +/// \param pstPixelConvertParam [IN][OUT] 像素格式转换参数结构体 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持转化成目标像素格式gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8 / gvspPixelBGRA8\n +/// 通过该接口将原始图像数据转换成用户所需的像素格式并存放在调用者指定内存中。\n +/// 像素格式为YUV411Packed的时,图像宽须能被4整除\n +/// 像素格式为YUV422Packed的时,图像宽须能被2整除\n +/// 像素格式为YUYVPacked的时,图像宽须能被2整除\n +/// 转换后的图像:数据存储是从最上面第一行开始的,这个是相机数据的默认存储方向 +/// \~english +/// \brief Pixel format conversion +/// \param handle [IN] Device handle +/// \param pstPixelConvertParam [IN][OUT] Convert Pixel Type parameter structure +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only support converting to destination pixel format of gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8 / gvspPixelBGRA8\n +/// This API is used to transform the collected original data to pixel format and save to specified memory by caller.\n +/// pixelFormat:YUV411Packed, the image width is divisible by 4\n +/// pixelFormat : YUV422Packed, the image width is divisible by 2\n +/// pixelFormat : YUYVPacked,the image width is divisible by 2\n +/// converted image:The first row of the image is located at the start of the image buffer.This is the default for image taken by a camera. +IMV_API int IMV_CALL IMV_PixelConvert(IN IMV_HANDLE handle, IN_OUT IMV_PixelConvertParam* pstPixelConvertParam); + +/// \~chinese +/// \brief 打开录像 +/// \param handle [IN] 设备句柄 +/// \param pstRecordParam [IN] 录像参数结构体 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Open record +/// \param handle [IN] Device handle +/// \param pstRecordParam [IN] Record param structure +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_OpenRecord(IN IMV_HANDLE handle, IN IMV_RecordParam *pstRecordParam); + +/// \~chinese +/// \brief 录制一帧图像 +/// \param handle [IN] 设备句柄 +/// \param pstRecordFrameInfoParam [IN] 录像用帧信息结构体 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Record one frame +/// \param handle [IN] Device handle +/// \param pstRecordFrameInfoParam [IN] Frame information for recording structure +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_InputOneFrame(IN IMV_HANDLE handle, IN IMV_RecordFrameInfoParam *pstRecordFrameInfoParam); + +/// \~chinese +/// \brief 关闭录像 +/// \param handle [IN] 设备句柄 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \~english +/// \brief Close record +/// \param handle [IN] Device handle +/// \return Success, return IMV_OK. Failure, return error code +IMV_API int IMV_CALL IMV_CloseRecord(IN IMV_HANDLE handle); + +/// \~chinese +/// \brief 图像翻转 +/// \param handle [IN] 设备句柄 +/// \param pstFlipImageParam [IN][OUT] 图像翻转参数结构体 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持像素格式gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8的图像的垂直和水平翻转。\n +/// 通过该接口将原始图像数据翻转后并存放在调用者指定内存中。 +/// \~english +/// \brief Flip image +/// \param handle [IN] Device handle +/// \param pstFlipImageParam [IN][OUT] Flip image parameter structure +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only support vertical and horizontal flip of image data with gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8 pixel format.\n +/// This API is used to flip original data and save to specified memory by caller. +IMV_API int IMV_CALL IMV_FlipImage(IN IMV_HANDLE handle, IN_OUT IMV_FlipImageParam* pstFlipImageParam); + +/// \~chinese +/// \brief 图像顺时针旋转 +/// \param handle [IN] 设备句柄 +/// \param pstRotateImageParam [IN][OUT] 图像旋转参数结构体 +/// \return 成功,返回IMV_OK;错误,返回错误码 +/// \remarks +/// 只支持gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8格式数据的90/180/270度顺时针旋转。\n +/// 通过该接口将原始图像数据旋转后并存放在调用者指定内存中。 +/// \~english +/// \brief Rotate image clockwise +/// \param handle [IN] Device handle +/// \param pstRotateImageParam [IN][OUT] Rotate image parameter structure +/// \return Success, return IMV_OK. Failure, return error code +/// \remarks +/// Only support 90/180/270 clockwise rotation of data in the gvspPixelRGB8 / gvspPixelBGR8 / gvspPixelMono8 format.\n +/// This API is used to rotation original data and save to specified memory by caller. +IMV_API int IMV_CALL IMV_RotateImage(IN IMV_HANDLE handle, IN_OUT IMV_RotateImageParam* pstRotateImageParam); + +#ifdef __cplusplus +} +#endif + +#endif // __IMV_API_H__ \ No newline at end of file diff --git a/camera_driver/include/IMVDefines.h b/camera_driver/include/IMVDefines.h new file mode 100644 index 0000000..bb1386d --- /dev/null +++ b/camera_driver/include/IMVDefines.h @@ -0,0 +1,811 @@ +#ifndef __IMV_DEFINES_H__ +#define __IMV_DEFINES_H__ + +#ifdef WIN32 +typedef __int64 int64_t; +typedef unsigned __int64 uint64_t; +#else +#include +#endif + +#ifndef IN +#define IN ///< \~chinese 输入型参数 \~english Input param +#endif + +#ifndef OUT +#define OUT ///< \~chinese 输出型参数 \~english Output param +#endif + +#ifndef IN_OUT +#define IN_OUT ///< \~chinese 输入/输出型参数 \~english Input/Output param +#endif + +#ifndef __cplusplus +typedef char bool; +#define true 1 +#define false 0 +#endif + +/// \~chinese +/// \brief 错误码 +/// \~english +/// \brief Error code +#define IMV_OK 0 ///< \~chinese 成功,无错误 \~english Successed, no error +#define IMV_ERROR -101 ///< \~chinese 通用的错误 \~english Generic error +#define IMV_INVALID_HANDLE -102 ///< \~chinese 错误或无效的句柄 \~english Error or invalid handle +#define IMV_INVALID_PARAM -103 ///< \~chinese 错误的参数 \~english Incorrect parameter +#define IMV_INVALID_FRAME_HANDLE -104 ///< \~chinese 错误或无效的帧句柄 \~english Error or invalid frame handle +#define IMV_INVALID_FRAME -105 ///< \~chinese 无效的帧 \~english Invalid frame +#define IMV_INVALID_RESOURCE -106 ///< \~chinese 相机/事件/流等资源无效 \~english Camera/Event/Stream and so on resource invalid +#define IMV_INVALID_IP -107 ///< \~chinese 设备与主机的IP网段不匹配 \~english Device's and PC's subnet is mismatch +#define IMV_NO_MEMORY -108 ///< \~chinese 内存不足 \~english Malloc memery failed +#define IMV_INSUFFICIENT_MEMORY -109 ///< \~chinese 传入的内存空间不足 \~english Insufficient memory +#define IMV_ERROR_PROPERTY_TYPE -110 ///< \~chinese 属性类型错误 \~english Property type error +#define IMV_INVALID_ACCESS -111 ///< \~chinese 属性不可访问、或不能读/写、或读/写失败 \~english Property not accessible, or not be read/written, or read/written failed +#define IMV_INVALID_RANGE -112 ///< \~chinese 属性值超出范围、或者不是步长整数倍 \~english The property's value is out of range, or is not integer multiple of the step +#define IMV_NOT_SUPPORT -113 ///< \~chinese 设备不支持的功能 \~english Device not supported function + +#define IMV_MAX_DEVICE_ENUM_NUM 100 ///< \~chinese 支持设备最大个数 \~english The maximum number of supported devices +#define IMV_MAX_STRING_LENTH 256 ///< \~chinese 字符串最大长度 \~english The maximum length of string +#define IMV_MAX_ERROR_LIST_NUM 128 ///< \~chinese 失败属性列表最大长度 \~english The maximum size of failed properties list + +typedef void* IMV_HANDLE; ///< \~chinese 设备句柄 \~english Device handle +typedef void* IMV_FRAME_HANDLE; ///< \~chinese 帧句柄 \~english Frame handle + +/// \~chinese +///枚举:接口类型 +/// \~english +///Enumeration: interface type +typedef enum _IMV_EInterfaceType +{ + interfaceTypeGige = 0x00000001, ///< \~chinese 网卡接口类型 \~english NIC type + interfaceTypeUsb3 = 0x00000002, ///< \~chinese USB3.0接口类型 \~english USB3.0 interface type + interfaceTypeCL = 0x00000004, ///< \~chinese CAMERALINK接口类型 \~english Cameralink interface type + interfaceTypePCIe = 0x00000008, ///< \~chinese PCIe接口类型 \~english PCIe interface type + interfaceTypeAll = 0x00000000, ///< \~chinese 忽略接口类型 \~english All types interface type + interfaceInvalidType = 0xFFFFFFFF ///< \~chinese 无效接口类型 \~english Invalid interface type +}IMV_EInterfaceType; + +/// \~chinese +///枚举:设备类型 +/// \~english +///Enumeration: device type +typedef enum _IMV_ECameraType +{ + typeGigeCamera = 0, ///< \~chinese GIGE相机 \~english GigE Vision Camera + typeU3vCamera = 1, ///< \~chinese USB3.0相机 \~english USB3.0 Vision Camera + typeCLCamera = 2, ///< \~chinese CAMERALINK 相机 \~english Cameralink camera + typePCIeCamera = 3, ///< \~chinese PCIe相机 \~english PCIe Camera + typeUndefinedCamera = 255 ///< \~chinese 未知类型 \~english Undefined Camera +}IMV_ECameraType; + +/// \~chinese +///枚举:创建句柄方式 +/// \~english +///Enumeration: Create handle mode +typedef enum _IMV_ECreateHandleMode +{ + modeByIndex = 0, ///< \~chinese 通过已枚举设备的索引(从0开始,比如 0, 1, 2...) \~english By index of enumerated devices (Start from 0, such as 0, 1, 2...) + modeByCameraKey, ///< \~chinese 通过设备键"厂商:序列号" \~english By device's key "vendor:serial number" + modeByDeviceUserID, ///< \~chinese 通过设备自定义名 \~english By device userID + modeByIPAddress, ///< \~chinese 通过设备IP地址 \~english By device IP address. +}IMV_ECreateHandleMode; + +/// \~chinese +///枚举:访问权限 +/// \~english +///Enumeration: access permission +typedef enum _IMV_ECameraAccessPermission +{ + accessPermissionOpen = 0, ///< \~chinese GigE相机没有被连接 \~english The GigE vision device isn't connected to any application. + accessPermissionExclusive, ///< \~chinese 独占访问权限 \~english Exclusive Access Permission + accessPermissionControl, ///< \~chinese 非独占可读访问权限 \~english Non-Exclusive Readbale Access Permission + accessPermissionControlWithSwitchover, ///< \~chinese 切换控制访问权限 \~english Control access with switchover enabled. + accessPermissionUnknown = 254, ///< \~chinese 无法确定 \~english Value not known; indeterminate. + accessPermissionUndefined ///< \~chinese 未定义访问权限 \~english Undefined Access Permission +}IMV_ECameraAccessPermission; + +/// \~chinese +///枚举:抓图策略 +/// \~english +///Enumeration: grab strartegy +typedef enum _IMV_EGrabStrategy +{ + grabStrartegySequential = 0, ///< \~chinese 按到达顺序处理图片 \~english The images are processed in the order of their arrival + grabStrartegyLatestImage = 1, ///< \~chinese 获取最新的图片 \~english Get latest image + grabStrartegyUpcomingImage = 2, ///< \~chinese 等待获取下一张图片(只针对GigE相机) \~english Waiting for next image(GigE only) + grabStrartegyUndefined ///< \~chinese 未定义 \~english Undefined +}IMV_EGrabStrategy; + +/// \~chinese +///枚举:流事件状态 +/// \~english +/// Enumeration:stream event status +typedef enum _IMV_EEventStatus +{ + streamEventNormal = 1, ///< \~chinese 正常流事件 \~english Normal stream event + streamEventLostFrame = 2, ///< \~chinese 丢帧事件 \~english Lost frame event + streamEventLostPacket = 3, ///< \~chinese 丢包事件 \~english Lost packet event + streamEventImageError = 4, ///< \~chinese 图像错误事件 \~english Error image event + streamEventStreamChannelError = 5, ///< \~chinese 取流错误事件 \~english Stream channel error event + streamEventTooManyConsecutiveResends = 6, ///< \~chinese 太多连续重传 \~english Too many consecutive resends event + streamEventTooManyLostPacket = 7 ///< \~chinese 太多丢包 \~english Too many lost packet event +}IMV_EEventStatus; + +/// \~chinese +///枚举:图像转换Bayer格式所用的算法 +/// \~english +/// Enumeration:alorithm used for Bayer demosaic +typedef enum _IMV_EBayerDemosaic +{ + demosaicNearestNeighbor, ///< \~chinese 最近邻 \~english Nearest neighbor + demosaicBilinear, ///< \~chinese 双线性 \~english Bilinear + demosaicEdgeSensing, ///< \~chinese 边缘检测 \~english Edge sensing + demosaicNotSupport = 255, ///< \~chinese 不支持 \~english Not support +}IMV_EBayerDemosaic; + +/// \~chinese +///枚举:事件类型 +/// \~english +/// Enumeration:event type +typedef enum _IMV_EVType +{ + offLine, ///< \~chinese 设备离线通知 \~english device offline notification + onLine ///< \~chinese 设备在线通知 \~english device online notification +}IMV_EVType; + +/// \~chinese +///枚举:视频格式 +/// \~english +/// Enumeration:Video format +typedef enum _IMV_EVideoType +{ + typeVideoFormatAVI = 0, ///< \~chinese AVI格式 \~english AVI format + typeVideoFormatNotSupport = 255 ///< \~chinese 不支持 \~english Not support +}IMV_EVideoType; + +/// \~chinese +///枚举:图像翻转类型 +/// \~english +/// Enumeration:Image flip type +typedef enum _IMV_EFlipType +{ + typeFlipVertical, ///< \~chinese 垂直(Y轴)翻转 \~english Vertical(Y-axis) flip + typeFlipHorizontal ///< \~chinese 水平(X轴)翻转 \~english Horizontal(X-axis) flip +}IMV_EFlipType; + +/// \~chinese +///枚举:顺时针旋转角度 +/// \~english +/// Enumeration:Rotation angle clockwise +typedef enum _IMV_ERotationAngle +{ + rotationAngle90, ///< \~chinese 顺时针旋转90度 \~english Rotate 90 degree clockwise + rotationAngle180, ///< \~chinese 顺时针旋转180度 \~english Rotate 180 degree clockwise + rotationAngle270, ///< \~chinese 顺时针旋转270度 \~english Rotate 270 degree clockwise +}IMV_ERotationAngle; + +#define IMV_GVSP_PIX_MONO 0x01000000 +#define IMV_GVSP_PIX_RGB 0x02000000 +#define IMV_GVSP_PIX_COLOR 0x02000000 +#define IMV_GVSP_PIX_CUSTOM 0x80000000 +#define IMV_GVSP_PIX_COLOR_MASK 0xFF000000 + +// Indicate effective number of bits occupied by the pixel (including padding). +// This can be used to compute amount of memory required to store an image. +#define IMV_GVSP_PIX_OCCUPY1BIT 0x00010000 +#define IMV_GVSP_PIX_OCCUPY2BIT 0x00020000 +#define IMV_GVSP_PIX_OCCUPY4BIT 0x00040000 +#define IMV_GVSP_PIX_OCCUPY8BIT 0x00080000 +#define IMV_GVSP_PIX_OCCUPY12BIT 0x000C0000 +#define IMV_GVSP_PIX_OCCUPY16BIT 0x00100000 +#define IMV_GVSP_PIX_OCCUPY24BIT 0x00180000 +#define IMV_GVSP_PIX_OCCUPY32BIT 0x00200000 +#define IMV_GVSP_PIX_OCCUPY36BIT 0x00240000 +#define IMV_GVSP_PIX_OCCUPY48BIT 0x00300000 + +/// \~chinese +///枚举:图像格式 +/// \~english +/// Enumeration:image format +typedef enum _IMV_EPixelType +{ + // Undefined pixel type + gvspPixelTypeUndefined = -1, + + // Mono Format + gvspPixelMono1p = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY1BIT | 0x0037), + gvspPixelMono2p = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY2BIT | 0x0038), + gvspPixelMono4p = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY4BIT | 0x0039), + gvspPixelMono8 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x0001), + gvspPixelMono8S = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x0002), + gvspPixelMono10 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0003), + gvspPixelMono10Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0004), + gvspPixelMono12 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0005), + gvspPixelMono12Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0006), + gvspPixelMono14 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0025), + gvspPixelMono16 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0007), + + // Bayer Format + gvspPixelBayGR8 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x0008), + gvspPixelBayRG8 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x0009), + gvspPixelBayGB8 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x000A), + gvspPixelBayBG8 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY8BIT | 0x000B), + gvspPixelBayGR10 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x000C), + gvspPixelBayRG10 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x000D), + gvspPixelBayGB10 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x000E), + gvspPixelBayBG10 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x000F), + gvspPixelBayGR12 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0010), + gvspPixelBayRG12 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0011), + gvspPixelBayGB12 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0012), + gvspPixelBayBG12 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0013), + gvspPixelBayGR10Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0026), + gvspPixelBayRG10Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0027), + gvspPixelBayGB10Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0028), + gvspPixelBayBG10Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x0029), + gvspPixelBayGR12Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x002A), + gvspPixelBayRG12Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x002B), + gvspPixelBayGB12Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x002C), + gvspPixelBayBG12Packed = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY12BIT | 0x002D), + gvspPixelBayGR16 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x002E), + gvspPixelBayRG16 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x002F), + gvspPixelBayGB16 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0030), + gvspPixelBayBG16 = (IMV_GVSP_PIX_MONO | IMV_GVSP_PIX_OCCUPY16BIT | 0x0031), + + // RGB Format + gvspPixelRGB8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x0014), + gvspPixelBGR8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x0015), + gvspPixelRGBA8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY32BIT | 0x0016), + gvspPixelBGRA8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY32BIT | 0x0017), + gvspPixelRGB10 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0018), + gvspPixelBGR10 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0019), + gvspPixelRGB12 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x001A), + gvspPixelBGR12 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x001B), + gvspPixelRGB16 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0033), + gvspPixelRGB10V1Packed = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY32BIT | 0x001C), + gvspPixelRGB10P32 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY32BIT | 0x001D), + gvspPixelRGB12V1Packed = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY36BIT | 0X0034), + gvspPixelRGB565P = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0035), + gvspPixelBGR565P = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0X0036), + + // YVR Format + gvspPixelYUV411_8_UYYVYY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY12BIT | 0x001E), + gvspPixelYUV422_8_UYVY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x001F), + gvspPixelYUV422_8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0032), + gvspPixelYUV8_UYV = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x0020), + gvspPixelYCbCr8CbYCr = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x003A), + gvspPixelYCbCr422_8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x003B), + gvspPixelYCbCr422_8_CbYCrY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0043), + gvspPixelYCbCr411_8_CbYYCrYY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY12BIT | 0x003C), + gvspPixelYCbCr601_8_CbYCr = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x003D), + gvspPixelYCbCr601_422_8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x003E), + gvspPixelYCbCr601_422_8_CbYCrY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0044), + gvspPixelYCbCr601_411_8_CbYYCrYY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY12BIT | 0x003F), + gvspPixelYCbCr709_8_CbYCr = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x0040), + gvspPixelYCbCr709_422_8 = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0041), + gvspPixelYCbCr709_422_8_CbYCrY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY16BIT | 0x0045), + gvspPixelYCbCr709_411_8_CbYYCrYY = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY12BIT | 0x0042), + + // RGB Planar + gvspPixelRGB8Planar = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY24BIT | 0x0021), + gvspPixelRGB10Planar = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0022), + gvspPixelRGB12Planar = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0023), + gvspPixelRGB16Planar = (IMV_GVSP_PIX_COLOR | IMV_GVSP_PIX_OCCUPY48BIT | 0x0024), + + //BayerRG10p和BayerRG12p格式,针对特定项目临时添加,请不要使用 + //BayerRG10p and BayerRG12p, currently used for specific project, please do not use them + gvspPixelBayRG10p = 0x010A0058, + gvspPixelBayRG12p = 0x010c0059, + + //mono1c格式,自定义格式 + //mono1c, customized image format, used for binary output + gvspPixelMono1c = 0x012000FF, + + //mono1e格式,自定义格式,用来显示连通域 + //mono1e, customized image format, used for displaying connected domain + gvspPixelMono1e = 0x01080FFF +}IMV_EPixelType; + +/// \~chinese +/// \brief 字符串信息 +/// \~english +/// \brief String information +typedef struct _IMV_String +{ + char str[IMV_MAX_STRING_LENTH]; ///< \~chinese 字符串.长度不超过256 \~english Strings and the maximum length of strings is 255. +}IMV_String; + +/// \~chinese +/// \brief GigE网卡信息 +/// \~english +/// \brief GigE interface information +typedef struct _IMV_GigEInterfaceInfo +{ + char description[IMV_MAX_STRING_LENTH]; ///< \~chinese 网卡描述信息 \~english Network card description + char macAddress[IMV_MAX_STRING_LENTH]; ///< \~chinese 网卡Mac地址 \~english Network card MAC Address + char ipAddress[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备Ip地址 \~english Device ip Address + char subnetMask[IMV_MAX_STRING_LENTH]; ///< \~chinese 子网掩码 \~english SubnetMask + char defaultGateWay[IMV_MAX_STRING_LENTH]; ///< \~chinese 默认网关 \~english Default GateWay + char chReserved[5][IMV_MAX_STRING_LENTH]; ///< 保留 \~english Reserved field +}IMV_GigEInterfaceInfo; + +/// \~chinese +/// \brief USB接口信息 +/// \~english +/// \brief USB interface information +typedef struct _IMV_UsbInterfaceInfo +{ + char description[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口描述信息 \~english USB interface description + char vendorID[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口Vendor ID \~english USB interface Vendor ID + char deviceID[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口设备ID \~english USB interface Device ID + char subsystemID[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口Subsystem ID \~english USB interface Subsystem ID + char revision[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口Revision \~english USB interface Revision + char speed[IMV_MAX_STRING_LENTH]; ///< \~chinese USB接口speed \~english USB interface speed + char chReserved[4][IMV_MAX_STRING_LENTH]; ///< 保留 \~english Reserved field +}IMV_UsbInterfaceInfo; + +/// \~chinese +/// \brief GigE设备信息 +/// \~english +/// \brief GigE device information +typedef struct _IMV_GigEDeviceInfo +{ + /// \~chinese + /// 设备支持的IP配置选项\n + /// value:4 相机只支持LLA\n + /// value:5 相机支持LLA和Persistent IP\n + /// value:6 相机支持LLA和DHCP\n + /// value:7 相机支持LLA、DHCP和Persistent IP\n + /// value:0 获取失败 + /// \~english + /// Supported IP configuration options of device\n + /// value:4 Device supports LLA \n + /// value:5 Device supports LLA and Persistent IP\n + /// value:6 Device supports LLA and DHCP\n + /// value:7 Device supports LLA, DHCP and Persistent IP\n + /// value:0 Get fail + unsigned int nIpConfigOptions; + /// \~chinese + /// 设备当前的IP配置选项\n + /// value:4 LLA处于活动状态\n + /// value:5 LLA和Persistent IP处于活动状态\n + /// value:6 LLA和DHCP处于活动状态\n + /// value:7 LLA、DHCP和Persistent IP处于活动状态\n + /// value:0 获取失败 + /// \~english + /// Current IP Configuration options of device\n + /// value:4 LLA is active\n + /// value:5 LLA and Persistent IP are active\n + /// value:6 LLA and DHCP are active\n + /// value:7 LLA, DHCP and Persistent IP are active\n + /// value:0 Get fail + unsigned int nIpConfigCurrent; + unsigned int nReserved[3]; ///< \~chinese 保留 \~english Reserved field + + char macAddress[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备Mac地址 \~english Device MAC Address + char ipAddress[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备Ip地址 \~english Device ip Address + char subnetMask[IMV_MAX_STRING_LENTH]; ///< \~chinese 子网掩码 \~english SubnetMask + char defaultGateWay[IMV_MAX_STRING_LENTH]; ///< \~chinese 默认网关 \~english Default GateWay + char protocolVersion[IMV_MAX_STRING_LENTH]; ///< \~chinese 网络协议版本 \~english Net protocol version + /// \~chinese + /// Ip配置有效性\n + /// Ip配置有效时字符串值"Valid"\n + /// Ip配置无效时字符串值"Invalid On This Interface" + /// \~english + /// IP configuration valid\n + /// String value is "Valid" when ip configuration valid\n + /// String value is "Invalid On This Interface" when ip configuration invalid + char ipConfiguration[IMV_MAX_STRING_LENTH]; + char chReserved[6][IMV_MAX_STRING_LENTH]; ///< \~chinese 保留 \~english Reserved field + +}IMV_GigEDeviceInfo; + +/// \~chinese +/// \brief Usb设备信息 +/// \~english +/// \brief Usb device information +typedef struct _IMV_UsbDeviceInfo +{ + bool bLowSpeedSupported; ///< \~chinese true支持,false不支持,其他值 非法。 \~english true support,false not supported,other invalid + bool bFullSpeedSupported; ///< \~chinese true支持,false不支持,其他值 非法。 \~english true support,false not supported,other invalid + bool bHighSpeedSupported; ///< \~chinese true支持,false不支持,其他值 非法。 \~english true support,false not supported,other invalid + bool bSuperSpeedSupported; ///< \~chinese true支持,false不支持,其他值 非法。 \~english true support,false not supported,other invalid + bool bDriverInstalled; ///< \~chinese true安装,false未安装,其他值 非法。 \~english true support,false not supported,other invalid + bool boolReserved[3]; ///< \~chinese 保留 + unsigned int Reserved[4]; ///< \~chinese 保留 \~english Reserved field + + char configurationValid[IMV_MAX_STRING_LENTH]; ///< \~chinese 配置有效性 \~english Configuration Valid + char genCPVersion[IMV_MAX_STRING_LENTH]; ///< \~chinese GenCP 版本 \~english GenCP Version + char u3vVersion[IMV_MAX_STRING_LENTH]; ///< \~chinese U3V 版本号 \~english U3v Version + char deviceGUID[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备引导号 \~english Device guid number + char familyName[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备系列号 \~english Device serial number + char u3vSerialNumber[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备序列号 \~english Device SerialNumber + char speed[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备传输速度 \~english Device transmission speed + char maxPower[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备最大供电量 \~english Maximum power supply of device + char chReserved[4][IMV_MAX_STRING_LENTH]; ///< \~chinese 保留 \~english Reserved field + +}IMV_UsbDeviceInfo; + +/// \~chinese +/// \brief 设备通用信息 +/// \~english +/// \brief Device general information +typedef struct _IMV_DeviceInfo +{ + IMV_ECameraType nCameraType; ///< \~chinese 设备类别 \~english Camera type + int nCameraReserved[5]; ///< \~chinese 保留 \~english Reserved field + + char cameraKey[IMV_MAX_STRING_LENTH]; ///< \~chinese 厂商:序列号 \~english Camera key + char cameraName[IMV_MAX_STRING_LENTH]; ///< \~chinese 用户自定义名 \~english UserDefinedName + char serialNumber[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备序列号 \~english Device SerialNumber + char vendorName[IMV_MAX_STRING_LENTH]; ///< \~chinese 厂商 \~english Camera Vendor + char modelName[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备型号 \~english Device model + char manufactureInfo[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备制造信息 \~english Device ManufactureInfo + char deviceVersion[IMV_MAX_STRING_LENTH]; ///< \~chinese 设备版本 \~english Device Version + char cameraReserved[5][IMV_MAX_STRING_LENTH]; ///< \~chinese 保留 \~english Reserved field + union + { + IMV_GigEDeviceInfo gigeDeviceInfo; ///< \~chinese Gige设备信息 \~english Gige Device Information + IMV_UsbDeviceInfo usbDeviceInfo; ///< \~chinese Usb设备信息 \~english Usb Device Information + }DeviceSpecificInfo; + + IMV_EInterfaceType nInterfaceType; ///< \~chinese 接口类别 \~english Interface type + int nInterfaceReserved[5]; ///< \~chinese 保留 \~english Reserved field + char interfaceName[IMV_MAX_STRING_LENTH]; ///< \~chinese 接口名 \~english Interface Name + char interfaceReserved[5][IMV_MAX_STRING_LENTH]; ///< \~chinese 保留 \~english Reserved field + union + { + IMV_GigEInterfaceInfo gigeInterfaceInfo; ///< \~chinese GigE网卡信息 \~english Gige interface Information + IMV_UsbInterfaceInfo usbInterfaceInfo; ///< \~chinese Usb接口信息 \~english Usb interface Information + }InterfaceInfo; +}IMV_DeviceInfo; + +/// \~chinese +/// \brief 加载失败的属性信息 +/// \~english +/// \brief Load failed properties information +typedef struct _IMV_ErrorList +{ + unsigned int nParamCnt; ///< \~chinese 加载失败的属性个数 \~english The count of load failed properties + IMV_String paramNameList[IMV_MAX_ERROR_LIST_NUM]; ///< \~chinese 加载失败的属性集合,上限128 \~english Array of load failed properties, up to 128 +}IMV_ErrorList; + +/// \~chinese +/// \brief 设备信息列表 +/// \~english +/// \brief Device information list +typedef struct _IMV_DeviceList +{ + unsigned int nDevNum; ///< \~chinese 设备数量 \~english Device Number + IMV_DeviceInfo* pDevInfo; ///< \~chinese 设备息列表(SDK内部缓存),最多100设备 \~english Device information list(cached within the SDK), up to 100 +}IMV_DeviceList; + +/// \~chinese +/// \brief 连接事件信息 +/// \~english +/// \brief connection event information +typedef struct _IMV_SConnectArg +{ + IMV_EVType event; ///< \~chinese 事件类型 \~english event type + unsigned int nReserve[10]; ///< \~chinese 预留字段 \~english Reserved field +}IMV_SConnectArg; + +/// \~chinese +/// \brief 参数更新事件信息 +/// \~english +/// \brief Updating parameters event information +typedef struct _IMV_SParamUpdateArg +{ + bool isPoll; ///< \~chinese 是否是定时更新,true:表示是定时更新,false:表示非定时更新 \~english Update periodically or not. true:update periodically, true:not update periodically + unsigned int nReserve[10]; ///< \~chinese 预留字段 \~english Reserved field + unsigned int nParamCnt; ///< \~chinese 更新的参数个数 \~english The number of parameters which need update + IMV_String* pParamNameList; ///< \~chinese 更新的参数名称集合(SDK内部缓存) \~english Array of parameter's name which need to be updated(cached within the SDK) +}IMV_SParamUpdateArg; + +/// \~chinese +/// \brief 流事件信息 +/// \~english +/// \brief Stream event information +typedef struct _IMV_SStreamArg +{ + unsigned int channel; ///< \~chinese 流通道号 \~english Channel no. + uint64_t blockId; ///< \~chinese 流数据BlockID \~english Block ID of stream data + uint64_t timeStamp; ///< \~chinese 时间戳 \~english Event time stamp + IMV_EEventStatus eStreamEventStatus; ///< \~chinese 流事件状态码 \~english Stream event status code + unsigned int status; ///< \~chinese 事件状态错误码 \~english Status error code + unsigned int nReserve[9]; ///< \~chinese 预留字段 \~english Reserved field +}IMV_SStreamArg; + +/// \~chinese +/// 消息通道事件ID列表 +/// \~english +/// message channel event id list +#define IMV_MSG_EVENT_ID_EXPOSURE_END 0x9001 +#define IMV_MSG_EVENT_ID_FRAME_TRIGGER 0x9002 +#define IMV_MSG_EVENT_ID_FRAME_START 0x9003 +#define IMV_MSG_EVENT_ID_ACQ_START 0x9004 +#define IMV_MSG_EVENT_ID_ACQ_TRIGGER 0x9005 +#define IMV_MSG_EVENT_ID_DATA_READ_OUT 0x9006 + +/// \~chinese +/// \brief 消息通道事件信息 +/// \~english +/// \brief Message channel event information +typedef struct _IMV_SMsgChannelArg +{ + unsigned short eventId; ///< \~chinese 事件Id \~english Event id + unsigned short channelId; ///< \~chinese 消息通道号 \~english Channel id + uint64_t blockId; ///< \~chinese 流数据BlockID \~english Block ID of stream data + uint64_t timeStamp; ///< \~chinese 时间戳 \~english Event timestamp + unsigned int nReserve[8]; ///< \~chinese 预留字段 \~english Reserved field + unsigned int nParamCnt; ///< \~chinese 参数个数 \~english The number of parameters which need update + IMV_String* pParamNameList; ///< \~chinese 事件相关的属性名列集合(SDK内部缓存) \~english Array of parameter's name which is related(cached within the SDK) +}IMV_SMsgChannelArg; + +/// \~chinese +/// \brief Chunk数据信息 +/// \~english +/// \brief Chunk data information +typedef struct _IMV_ChunkDataInfo +{ + unsigned int chunkID; ///< \~chinese ChunkID \~english ChunkID + unsigned int nParamCnt; ///< \~chinese 属性名个数 \~english The number of paramNames + IMV_String* pParamNameList; ///< \~chinese Chunk数据对应的属性名集合(SDK内部缓存) \~english ParamNames Corresponding property name of chunk data(cached within the SDK) +}IMV_ChunkDataInfo; + +/// \~chinese +/// \brief 帧图像信息 +/// \~english +/// \brief The frame image information +typedef struct _IMV_FrameInfo +{ + uint64_t blockId; ///< \~chinese 帧Id(仅对GigE/Usb/PCIe相机有效) \~english The block ID(GigE/Usb/PCIe camera only) + unsigned int status; ///< \~chinese 数据帧状态(0是正常状态) \~english The status of frame(0 is normal status) + unsigned int width; ///< \~chinese 图像宽度 \~english The width of image + unsigned int height; ///< \~chinese 图像高度 \~english The height of image + unsigned int size; ///< \~chinese 图像大小 \~english The size of image + IMV_EPixelType pixelFormat; ///< \~chinese 图像像素格式 \~english The pixel format of image + uint64_t timeStamp; ///< \~chinese 图像时间戳(仅对GigE/Usb/PCIe相机有效) \~english The timestamp of image(GigE/Usb/PCIe camera only) + unsigned int chunkCount; ///< \~chinese 帧数据中包含的Chunk个数(仅对GigE/Usb相机有效) \~english The number of chunk in frame data(GigE/Usb Camera Only) + unsigned int paddingX; ///< \~chinese 图像paddingX(仅对GigE/Usb/PCIe相机有效) \~english The paddingX of image(GigE/Usb/PCIe camera only) + unsigned int paddingY; ///< \~chinese 图像paddingY(仅对GigE/Usb/PCIe相机有效) \~english The paddingY of image(GigE/Usb/PCIe camera only) + unsigned int recvFrameTime; ///< \~chinese 图像在网络传输所用的时间(单位:微秒,非GigE相机该值为0) \~english The time taken for the image to be transmitted over the network(unit:us, The value is 0 for non-GigE camera) + unsigned int nReserved[19]; ///< \~chinese 预留字段 \~english Reserved field +}IMV_FrameInfo; + +/// \~chinese +/// \brief 帧图像数据信息 +/// \~english +/// \brief Frame image data information +typedef struct _IMV_Frame +{ + IMV_FRAME_HANDLE frameHandle; ///< \~chinese 帧图像句柄(SDK内部帧管理用) \~english Frame image handle(used for managing frame within the SDK) + unsigned char* pData; ///< \~chinese 帧图像数据的内存首地址 \~english The starting address of memory of image data + IMV_FrameInfo frameInfo; ///< \~chinese 帧信息 \~english Frame information + unsigned int nReserved[10]; ///< \~chinese 预留字段 \~english Reserved field +}IMV_Frame; + +/// \~chinese +/// \brief PCIE设备统计流信息 +/// \~english +/// \brief PCIE device stream statistics information +typedef struct _IMV_PCIEStreamStatsInfo +{ + unsigned int imageError; ///< \~chinese 图像错误的帧数 \~english Number of images error frames + unsigned int lostPacketBlock; ///< \~chinese 丢包的帧数 \~english Number of frames lost + unsigned int nReserved0[10]; ///< \~chinese 预留 \~english Reserved field + + unsigned int imageReceived; ///< \~chinese 正常获取的帧数 \~english Number of frames acquired + double fps; ///< \~chinese 帧率 \~english Frame rate + double bandwidth; ///< \~chinese 带宽(Mbps) \~english Bandwidth(Mbps) + unsigned int nReserved[8]; ///< \~chinese 预留 \~english Reserved field +}IMV_PCIEStreamStatsInfo; + +/// \~chinese +/// \brief U3V设备统计流信息 +/// \~english +/// \brief U3V device stream statistics information +typedef struct _IMV_U3VStreamStatsInfo +{ + unsigned int imageError; ///< \~chinese 图像错误的帧数 \~english Number of images error frames + unsigned int lostPacketBlock; ///< \~chinese 丢包的帧数 \~english Number of frames lost + unsigned int nReserved0[10]; ///< \~chinese 预留 \~english Reserved field + + unsigned int imageReceived; ///< \~chinese 正常获取的帧数 \~english Number of images error frames + double fps; ///< \~chinese 帧率 \~english Frame rate + double bandwidth; ///< \~chinese 带宽(Mbps) \~english Bandwidth(Mbps) + unsigned int nReserved[8]; ///< \~chinese 预留 \~english Reserved field +}IMV_U3VStreamStatsInfo; + +/// \~chinese +/// \brief Gige设备统计流信息 +/// \~english +/// \brief Gige device stream statistics information +typedef struct _IMV_GigEStreamStatsInfo +{ + unsigned int nReserved0[10]; ///< \~chinese 预留 \~english Reserved field + + unsigned int imageError; ///< \~chinese 图像错误的帧数 \~english Number of image error frames + unsigned int lostPacketBlock; ///< \~chinese 丢包的帧数 \~english Number of frames lost + unsigned int nReserved1[4]; ///< \~chinese 预留 \~english Reserved field + unsigned int nReserved2[5]; ///< \~chinese 预留 \~english Reserved field + + unsigned int imageReceived; ///< \~chinese 正常获取的帧数 \~english Number of frames acquired + double fps; ///< \~chinese 帧率 \~english Frame rate + double bandwidth; ///< \~chinese 带宽(Mbps) \~english Bandwidth(Mbps) + unsigned int nReserved[4]; ///< \~chinese 预留 \~english Reserved field +}IMV_GigEStreamStatsInfo; + +/// \~chinese +/// \brief 统计流信息 +/// \~english +/// \brief Stream statistics information +typedef struct _IMV_StreamStatisticsInfo +{ + IMV_ECameraType nCameraType; ///< \~chinese 设备类型 \~english Device type + + union + { + IMV_PCIEStreamStatsInfo pcieStatisticsInfo; ///< \~chinese PCIE设备统计信息 \~english PCIE device statistics information + IMV_U3VStreamStatsInfo u3vStatisticsInfo; ///< \~chinese U3V设备统计信息 \~english U3V device statistics information + IMV_GigEStreamStatsInfo gigeStatisticsInfo; ///< \~chinese Gige设备统计信息 \~english GIGE device statistics information + }; +}IMV_StreamStatisticsInfo; + +/// \~chinese +/// \brief 枚举属性的枚举值信息 +/// \~english +/// \brief Enumeration property 's enumeration value information +typedef struct _IMV_EnumEntryInfo +{ + uint64_t value; ///< \~chinese 枚举值 \~english Enumeration value + char name[IMV_MAX_STRING_LENTH]; ///< \~chinese symbol名 \~english Symbol name +}IMV_EnumEntryInfo; + +/// \~chinese +/// \brief 枚举属性的可设枚举值列表信息 +/// \~english +/// \brief Enumeration property 's settable enumeration value list information +typedef struct _IMV_EnumEntryList +{ + unsigned int nEnumEntryBufferSize; ///< \~chinese 存放枚举值内存大小 \~english The size of saving enumeration value + IMV_EnumEntryInfo* pEnumEntryInfo; ///< \~chinese 存放可设枚举值列表(调用者分配缓存) \~english Save the list of settable enumeration value(allocated cache by the caller) +}IMV_EnumEntryList; + +/// \~chinese +/// \brief 像素转换结构体 +/// \~english +/// \brief Pixel convert structure +typedef struct _IMV_PixelConvertParam +{ + unsigned int nWidth; ///< [IN] \~chinese 图像宽 \~english Width + unsigned int nHeight; ///< [IN] \~chinese 图像高 \~english Height + IMV_EPixelType ePixelFormat; ///< [IN] \~chinese 像素格式 \~english Pixel format + unsigned char* pSrcData; ///< [IN] \~chinese 输入图像数据 \~english Input image data + unsigned int nSrcDataLen; ///< [IN] \~chinese 输入图像长度 \~english Input image length + unsigned int nPaddingX; ///< [IN] \~chinese 图像宽填充 \~english Padding X + unsigned int nPaddingY; ///< [IN] \~chinese 图像高填充 \~english Padding Y + IMV_EBayerDemosaic eBayerDemosaic; ///< [IN] \~chinese 转换Bayer格式算法 \~english Alorithm used for Bayer demosaic + IMV_EPixelType eDstPixelFormat; ///< [IN] \~chinese 目标像素格式 \~english Destination pixel format + unsigned char* pDstBuf; ///< [OUT] \~chinese 输出数据缓存(调用者分配缓存) \~english Output data buffer(allocated cache by the caller) + unsigned int nDstBufSize; ///< [IN] \~chinese 提供的输出缓冲区大小 \~english Provided output buffer size + unsigned int nDstDataLen; ///< [OUT] \~chinese 输出数据长度 \~english Output data length + unsigned int nReserved[8]; ///< \~chinese 预留 \~english Reserved field +}IMV_PixelConvertParam; + +/// \~chinese +/// \brief 录像结构体 +/// \~english +/// \brief Record structure +typedef struct _IMV_RecordParam +{ + unsigned int nWidth; ///< [IN] \~chinese 图像宽 \~english Width + unsigned int nHeight; ///< [IN] \~chinese 图像高 \~english Height + float fFameRate; ///< [IN] \~chinese 帧率(大于0) \~english Frame rate(greater than 0) + unsigned int nQuality; ///< [IN] \~chinese 视频质量(1-100) \~english Video quality(1-100) + IMV_EVideoType recordFormat; ///< [IN] \~chinese 视频格式 \~english Video format + const char* pRecordFilePath; ///< [IN] \~chinese 保存视频路径 \~english Save video path + unsigned int nReserved[5]; ///< \~chinese 预留 \~english Reserved +}IMV_RecordParam; + +/// \~chinese +/// \brief 录像用帧信息结构体 +/// \~english +/// \brief Frame information for recording structure +typedef struct _IMV_RecordFrameInfoParam +{ + unsigned char* pData; ///< [IN] \~chinese 图像数据 \~english Image data + unsigned int nDataLen; ///< [IN] \~chinese 图像数据长度 \~english Image data length + unsigned int nPaddingX; ///< [IN] \~chinese 图像宽填充 \~english Padding X + unsigned int nPaddingY; ///< [IN] \~chinese 图像高填充 \~english Padding Y + IMV_EPixelType ePixelFormat; ///< [IN] \~chinese 像素格式 \~english Pixel format + unsigned int nReserved[5]; ///< \~chinese 预留 \~english Reserved +}IMV_RecordFrameInfoParam; + +/// \~chinese +/// \brief 图像翻转结构体 +/// \~english +/// \brief Flip image structure +typedef struct _IMV_FlipImageParam +{ + unsigned int nWidth; ///< [IN] \~chinese 图像宽 \~english Width + unsigned int nHeight; ///< [IN] \~chinese 图像高 \~english Height + IMV_EPixelType ePixelFormat; ///< [IN] \~chinese 像素格式 \~english Pixel format + IMV_EFlipType eFlipType; ///< [IN] \~chinese 翻转类型 \~english Flip type + unsigned char* pSrcData; ///< [IN] \~chinese 输入图像数据 \~english Input image data + unsigned int nSrcDataLen; ///< [IN] \~chinese 输入图像长度 \~english Input image length + unsigned char* pDstBuf; ///< [OUT] \~chinese 输出数据缓存(调用者分配缓存) \~english Output data buffer(allocated cache by the caller) + unsigned int nDstBufSize; ///< [IN] \~chinese 提供的输出缓冲区大小 \~english Provided output buffer size + unsigned int nDstDataLen; ///< [OUT] \~chinese 输出数据长度 \~english Output data length + unsigned int nReserved[8]; ///< \~chinese 预留 \~english Reserved +}IMV_FlipImageParam; + +/// \~chinese +/// \brief 图像旋转结构体 +/// \~english +/// \brief Rotate image structure +typedef struct _IMV_RotateImageParam +{ + unsigned int nWidth; ///< [IN][OUT] \~chinese 图像宽 \~english Width + unsigned int nHeight; ///< [IN][OUT] \~chinese 图像高 \~english Height + IMV_EPixelType ePixelFormat; ///< [IN] \~chinese 像素格式 \~english Pixel format + IMV_ERotationAngle eRotationAngle; ///< [IN] \~chinese 旋转角度 \~english Rotation angle + unsigned char* pSrcData; ///< [IN] \~chinese 输入图像数据 \~english Input image data + unsigned int nSrcDataLen; ///< [IN] \~chinese 输入图像长度 \~english Input image length + unsigned char* pDstBuf; ///< [OUT] \~chinese 输出数据缓存(调用者分配缓存) \~english Output data buffer(allocated cache by the caller) + unsigned int nDstBufSize; ///< [IN] \~chinese 提供的输出缓冲区大小 \~english Provided output buffer size + unsigned int nDstDataLen; ///< [OUT] \~chinese 输出数据长度 \~english Output data length + unsigned int nReserved[8]; ///< \~chinese 预留 \~english Reserved +}IMV_RotateImageParam; + +/// \~chinese +/// \brief 设备连接状态事件回调函数声明 +/// \param pParamUpdateArg [in] 回调时主动推送的设备连接状态事件信息 +/// \param pUser [in] 用户自定义数据 +/// \~english +/// \brief Call back function declaration of device connection status event +/// \param pStreamArg [in] The device connection status event which will be active pushed out during the callback +/// \param pUser [in] User defined data +typedef void(*IMV_ConnectCallBack)(const IMV_SConnectArg* pConnectArg, void* pUser); + +/// \~chinese +/// \brief 参数更新事件回调函数声明 +/// \param pParamUpdateArg [in] 回调时主动推送的参数更新事件信息 +/// \param pUser [in] 用户自定义数据 +/// \~english +/// \brief Call back function declaration of parameter update event +/// \param pStreamArg [in] The parameter update event which will be active pushed out during the callback +/// \param pUser [in] User defined data +typedef void(*IMV_ParamUpdateCallBack)(const IMV_SParamUpdateArg* pParamUpdateArg, void* pUser); + +/// \~chinese +/// \brief 流事件回调函数声明 +/// \param pStreamArg [in] 回调时主动推送的流事件信息 +/// \param pUser [in] 用户自定义数据 +/// \~english +/// \brief Call back function declaration of stream event +/// \param pStreamArg [in] The stream event which will be active pushed out during the callback +/// \param pUser [in] User defined data +typedef void(*IMV_StreamCallBack)(const IMV_SStreamArg* pStreamArg, void* pUser); + +/// \~chinese +/// \brief 消息通道事件回调函数声明 +/// \param pMsgChannelArg [in] 回调时主动推送的消息通道事件信息 +/// \param pUser [in] 用户自定义数据 +/// \~english +/// \brief Call back function declaration of message channel event +/// \param pMsgChannelArg [in] The message channel event which will be active pushed out during the callback +/// \param pUser [in] User defined data +typedef void(*IMV_MsgChannelCallBack)(const IMV_SMsgChannelArg* pMsgChannelArg, void* pUser); + +/// \~chinese +/// \brief 帧数据信息回调函数声明 +/// \param pFrame [in] 回调时主动推送的帧信息 +/// \param pUser [in] 用户自定义数据 +/// \~english +/// \brief Call back function declaration of frame data information +/// \param pFrame [in] The frame information which will be active pushed out during the callback +/// \param pUser [in] User defined data +typedef void(*IMV_FrameCallBack)(IMV_Frame* pFrame, void* pUser); + +#endif // __IMV_DEFINES_H__ \ No newline at end of file diff --git a/camera_driver/lib/GenICam/bin/Linux64_x64/libGCBase_gcc421_v3_0.so b/camera_driver/lib/GenICam/bin/Linux64_x64/libGCBase_gcc421_v3_0.so new file mode 100644 index 0000000..a749e9c Binary files /dev/null and b/camera_driver/lib/GenICam/bin/Linux64_x64/libGCBase_gcc421_v3_0.so differ diff --git a/camera_driver/lib/GenICam/bin/Linux64_x64/libGenApi_gcc421_v3_0.so b/camera_driver/lib/GenICam/bin/Linux64_x64/libGenApi_gcc421_v3_0.so new file mode 100644 index 0000000..6895642 Binary files /dev/null and b/camera_driver/lib/GenICam/bin/Linux64_x64/libGenApi_gcc421_v3_0.so differ diff --git a/camera_driver/lib/GenICam/bin/Linux64_x64/libLog_gcc421_v3_0.so b/camera_driver/lib/GenICam/bin/Linux64_x64/libLog_gcc421_v3_0.so new file mode 100644 index 0000000..8b7cbfd Binary files /dev/null and b/camera_driver/lib/GenICam/bin/Linux64_x64/libLog_gcc421_v3_0.so differ diff --git a/camera_driver/lib/GenICam/bin/Linux64_x64/libMathParser_gcc421_v3_0.so b/camera_driver/lib/GenICam/bin/Linux64_x64/libMathParser_gcc421_v3_0.so new file mode 100644 index 0000000..04050d2 Binary files /dev/null and b/camera_driver/lib/GenICam/bin/Linux64_x64/libMathParser_gcc421_v3_0.so differ diff --git a/camera_driver/lib/GenICam/bin/Linux64_x64/libNodeMapData_gcc421_v3_0.so b/camera_driver/lib/GenICam/bin/Linux64_x64/libNodeMapData_gcc421_v3_0.so new file mode 100644 index 0000000..3dac61c Binary files /dev/null and b/camera_driver/lib/GenICam/bin/Linux64_x64/libNodeMapData_gcc421_v3_0.so differ diff --git a/camera_driver/lib/GenICam/bin/Linux64_x64/libXmlParser_gcc421_v3_0.so b/camera_driver/lib/GenICam/bin/Linux64_x64/libXmlParser_gcc421_v3_0.so new file mode 100644 index 0000000..b93e919 Binary files /dev/null and b/camera_driver/lib/GenICam/bin/Linux64_x64/libXmlParser_gcc421_v3_0.so differ diff --git a/camera_driver/lib/GenICam/bin/Linux64_x64/liblog4cpp_gcc421_v3_0.so b/camera_driver/lib/GenICam/bin/Linux64_x64/liblog4cpp_gcc421_v3_0.so new file mode 100644 index 0000000..c2710a4 Binary files /dev/null and b/camera_driver/lib/GenICam/bin/Linux64_x64/liblog4cpp_gcc421_v3_0.so differ diff --git a/camera_driver/lib/GenICam/log/config-unix/DefaultLogging.properties b/camera_driver/lib/GenICam/log/config-unix/DefaultLogging.properties new file mode 100644 index 0000000..0452fee --- /dev/null +++ b/camera_driver/lib/GenICam/log/config-unix/DefaultLogging.properties @@ -0,0 +1,6 @@ +# These settings are loaded as default + +log4j.rootCategory=ERROR, Console +log4cpp.appender.Console=org.apache.log4j.ConsoleAppender +log4cpp.appender.Console.layout=org.apache.log4j.PatternLayout +log4cpp.appender.Console.layout.ConversionPattern==>LOG %x: %c : %m%n diff --git a/camera_driver/lib/GenICam/xml/GenApi/GenApiSchema_Version_1_0.xsd b/camera_driver/lib/GenICam/xml/GenApi/GenApiSchema_Version_1_0.xsd new file mode 100644 index 0000000..68ae0ec --- /dev/null +++ b/camera_driver/lib/GenICam/xml/GenApi/GenApiSchema_Version_1_0.xsd @@ -0,0 +1,741 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Cache on write and write into register + + + + + Write w/o cache, read updates cache + + + + + Do not perform caching + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/camera_driver/lib/GenICam/xml/GenApi/GenApiSchema_Version_1_1.xsd b/camera_driver/lib/GenICam/xml/GenApi/GenApiSchema_Version_1_1.xsd new file mode 100644 index 0000000..c73e6a8 --- /dev/null +++ b/camera_driver/lib/GenICam/xml/GenApi/GenApiSchema_Version_1_1.xsd @@ -0,0 +1,1221 @@ + + + + + + + + The outer element of a device description file. It contains a set of nodes which are connected + via pointers and which describe a mapping from features (like Gain) to a register space + defined in terms of address and length. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + List of all possible node types. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Used for structuring device description files. Groups can be nested in any depth. + They have no meaning with respect to the device functionality and are stripped off the device + description file in a pre-processing step. + + + + + + + + + + + Lists the elements which are common to (nearly) all nodes. + + + + + + + + + + + + + + + + + + + + + + + + + Lists the attributes which are common to all nodes. + + + + + + + + + + + Lists the elements which are common to all register nodes with a pLength element + + + + + + + + + + + + + + + + + + + + + + + + + + The simple node with no functionality. + + + + + + + + + + + + Contains references to features which are exposed to the user via API or GUI. + Can be nested in any depth. + + + + + + + + + + + + + Integer node which can be used to collect Value, Min, Max, and Inc or be used as Multiplexer + or be used as Replicator. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Maps to a register of Integer type. + + + + + + + + + + + + + + + + Maps to a subset (bit range) of a register of Integer type. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Describes a collection of subsets (bit ranges) on the same integer register + + + + + + + + + + + + + Describes a one subset (bit range) of a StructReg + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + A node for issuing commands. + + + + + + + + + + + + + + + + + + + + + A node for issuing boolean values based on an integer node + + + + + + + + + + + + + + + + + + + + Float node which can be used to collect Value, Min, and Max, or be used as Multiplexer. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Bi-directional Float Swiss-knife. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Bi-directional Integer Swiss-knife. + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Maps to a Float register. + + + + + + + + + + + + + + + + Enumeration mapping to an Integer. + + + + + + + + + + + + + + + + + + + + Possible value of an Enumeration node + + + + + + + + + + + + + + + + String node + + + + + + + + + + + + + + + + + String mapping to a register + + + + + + + + + + + Register exposed as byte array. + + + + + + + + + + + Uno-directional formula interpreter + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Uno-directional formula interpreter + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + Node mapping to a port accessing the device's registers. + + + + + + + + + + + + + + + + + + Accesses a IEEE1212 configuration ROM address block + + + + + + + + + + + + + + + + + + + + + + + + Accesses a Text entry in a IEEE1212 configuration ROM address block + + + + + + + + + + + + Accesses an Integer entry in a IEEE1212 configuration ROM address block + + + + + + + + + + + + Gets the address of a DCAM smart feature + + + + + + + + + + + + + Gets the address of a smart feature + + + + + + + + + + + + + + + + + + + Content to custom extend a device description file. The extension entries are stripped away + during pre-processing of the device description file. + + + + + + + + + + + + + + + + + + + + + + + + + + Cache on write and write into register + + + + + Write w/o cache, read updates cache + + + + + Do not perform caching + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/camera_driver/lib/GenICam/xml/GenApi/GenApi_Params_h.xsl b/camera_driver/lib/GenICam/xml/GenApi/GenApi_Params_h.xsl new file mode 100644 index 0000000..114ecfd --- /dev/null +++ b/camera_driver/lib/GenICam/xml/GenApi/GenApi_Params_h.xsl @@ -0,0 +1,376 @@ + + + + + + + + + + + +//----------------------------------------------------------------------------- +// (c) 2004-2008 by Basler Vision Technologies +// Section: Vision Components +// Project: GenApi +//----------------------------------------------------------------------------- +/*! +\file +\brief +*/ + +//----------------------------------------------------------------------------- +// This file is generated automatically +// Do not modify! +//----------------------------------------------------------------------------- + + + _ + + +#ifndef _PARAMS_H +#define _PARAMS_H + +#include <GenApi/IEnumerationT.h> +#include <GenApi/NodeMapRef.h> +#include <GenApi/DLLLoad.h> + +//! The namespace containing the device's control interface and related enumeration types +namespace +{ + + //************************************************************************************************** + // Enumerations + //************************************************************************************************** + + + //************************************************************************************************** + // Parameter class + //************************************************************************************************** + + C_Params + + + //! + class + { + //---------------------------------------------------------------------------------------------------------------- + // Implementation + //---------------------------------------------------------------------------------------------------------------- + protected: + // If you want to show the following methods in the help file + // add the string HIDE_CLASS_METHODS to the ENABLED_SECTIONS tag in the doxygen file + //! \cond HIDE_CLASS_METHODS + + //! Constructor + (void); + + //! Destructor + ~(void); + + //! Initializes the references + void _Initialize(GenApi::INodeMap*); + + //! Return the vendor of the camera + const char* _GetVendorName(void); + + //! Returns the camera model name + const char* _GetModelName(void); + + //! \endcond + + //---------------------------------------------------------------------------------------------------------------- + // References to features + //---------------------------------------------------------------------------------------------------------------- + public: + + + private: + //! \cond HIDE_CLASS_METHODS + + //! not implemented copy constructor + (&); + + //! not implemented assignment operator + & operator=(&); + + //! \endcond + }; + + + //************************************************************************************************** + // Parameter class implementation + //************************************************************************************************** + + //! \cond HIDE_CLASS_METHODS + + inline ::(void) + + { + } + + inline ::~(void) + { + + } + + inline void ::_Initialize(GenApi::INodeMap* _Ptr) + { + + } + + inline const char* ::_GetVendorName(void) + { + return ""; + } + + inline const char* ::_GetModelName(void) + { + return ""; + } + + //! \endcond + +} // namespace + +#endif // _PARAMS_H + + + + + + + + + + + + + //! Valid values for + enum Enums + { + + }; + + + + + + + + + + + + , + + + + + + + _ //!< + + + + + + + + + + + + + //! \name - + + + //! \name Miscellaneous Features + + + //@{ + /*! + \brief + + + + + + \b Visibility = + + + \b Visibility = Beginner + + + + \b Selected by : + + , + + + + */ + +# pragma deprecated( ) +# pragma warning(push) +# pragma warning(disable: 4995) // name has been marked as deprecated + + + + GenApi:: + T< + Enums > + + + GenApi:: + + + + & + ; + +# pragma warning(pop) + + //@} + + + + + + + + + + + + + + + + : + + + , + + + + +# pragma warning(push) +# pragma warning(disable: 4995) // name has been marked as deprecated + + + + ( *new GenApi::<Enums>() ) + + + ( *new GenApi::() ) + + + +# pragma warning(pop) + + + + + + + + + + + + +# pragma warning(push) +# pragma warning(disable: 4995) // name has been marked as deprecated + + + + delete static_cast < GenApi::<Enums> *> (& ); + + + delete static_cast < GenApi::*> (& ); + + + +# pragma warning(pop) + + + + + + + + + + + +# pragma warning(push) +# pragma warning(disable: 4995) // name has been marked as deprecated + + + + static_cast<GenApi::<Enums> *> (& )->SetReference(_Ptr->GetNode("")); + + + static_cast<GenApi::*> (& )->SetReference(_Ptr->GetNode("")); + + + + + static_cast<GenApi::<Enums> *> (& )->SetNumEnums(); + + + + + + +# pragma warning(pop) + + + + + + + + + + + + + + + + + + + + + + + static_cast<GenApi::CEnumerationTRef<Enums> *> (& )->SetEnumReference( _, "" ); + + + diff --git a/camera_driver/lib/GenICam/xml/GenApi/GenApi_Ptr_h.xsl b/camera_driver/lib/GenICam/xml/GenApi/GenApi_Ptr_h.xsl new file mode 100644 index 0000000..41cd8bd --- /dev/null +++ b/camera_driver/lib/GenICam/xml/GenApi/GenApi_Ptr_h.xsl @@ -0,0 +1,83 @@ + + + + + +Params.h + + + + + +//----------------------------------------------------------------------------- +// (c) 2004-2008 by Basler Vision Technologies +// Section: Vision Components +// Project: GenApi +//----------------------------------------------------------------------------- +/*! +\file +\brief +*/ +//----------------------------------------------------------------------------- +// This file is generated automatically +// Do not modify! +//----------------------------------------------------------------------------- + + _ + + +#ifndef _PTR_H +#define _PTR_H + +#include <GenApi/NodeMapRef.h> +#include "" + +//! The namespace containing the device's control interface and related enumeration types +namespace +{ + //************************************************************************************************** + // Access class + //************************************************************************************************** + //! + class C + : public GenApi::CNodeMapRefT<::C_Params> + { + public: + //! Constructor + C(GenICam::gcstring DeviceName = "Device") : GenApi::CNodeMapRefT<::C_Params>(DeviceName) + { + } + }; + + +} // namespace + +#endif // _PTR_H + + + + + diff --git a/camera_driver/lib/GenICam/xml/GenApi/NodeTypes.xml b/camera_driver/lib/GenICam/xml/GenApi/NodeTypes.xml new file mode 100644 index 0000000..44315d6 --- /dev/null +++ b/camera_driver/lib/GenICam/xml/GenApi/NodeTypes.xml @@ -0,0 +1,131 @@ + + + + + + CValueNode + IValue + CValueRef + + + CCategory + ICategory + CCategoryRef + + + CInteger + IInteger + CIntegerRef + + + CEnumeration + IEnumeration + CEnumerationTRef + + + CEnumEntry + IEnumEntry + CEnumEntryRef + + + CMaskedIntReg + IInteger + CIntegerRef + + + CRegister + IRegister + CRegisterRef + + + CIntReg + IInteger + CIntegerRef + + + CFloat + IFloat + CFloatRef + + + CFltReg + IFloat + CFloatRef + + + CSwissKnife + IFloat + CFloatRef + + + CIntSwissKnife + IInteger + CIntegerRef + + + CIntKey + IInteger + CIntegerRef + + + CTxtKey + IString + CStringRef + + + CPort + IPort + CPortRecorderRef + + + CIEEE1212Parser + IRegister + CRegisterRef + + + CDcamAccessCtrlReg + IInteger + CIntegerRef + + + CSmartFeature + IInteger + CIntegerRef + + + CStringNode + IString + CStringRef + + + CStringRegister + IString + CStringRef + + + CBoolean + IBoolean + CBooleanRef + + + CCommand + ICommand + CCommandRef + + + CConverter + IFloat + CFloatRef + + + CIntConverter + IInteger + CIntegerRef + + diff --git a/camera_driver/lib/GenICam/xml/GenApi/NodeTypes.xsd b/camera_driver/lib/GenICam/xml/GenApi/NodeTypes.xsd new file mode 100644 index 0000000..dc852e8 --- /dev/null +++ b/camera_driver/lib/GenICam/xml/GenApi/NodeTypes.xsd @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/camera_driver/lib/Qt/libQt5Core.so.5.5.1 b/camera_driver/lib/Qt/libQt5Core.so.5.5.1 new file mode 100644 index 0000000..71d7a30 Binary files /dev/null and b/camera_driver/lib/Qt/libQt5Core.so.5.5.1 differ diff --git a/camera_driver/lib/Qt/libQt5DBus.so.5.5.1 b/camera_driver/lib/Qt/libQt5DBus.so.5.5.1 new file mode 100644 index 0000000..302eb7a Binary files /dev/null and b/camera_driver/lib/Qt/libQt5DBus.so.5.5.1 differ diff --git a/camera_driver/lib/Qt/libQt5Gui.so.5.5.1 b/camera_driver/lib/Qt/libQt5Gui.so.5.5.1 new file mode 100644 index 0000000..741dffb Binary files /dev/null and b/camera_driver/lib/Qt/libQt5Gui.so.5.5.1 differ diff --git a/camera_driver/lib/Qt/libQt5Network.so.5.5.1 b/camera_driver/lib/Qt/libQt5Network.so.5.5.1 new file mode 100644 index 0000000..a0e56e7 Binary files /dev/null and b/camera_driver/lib/Qt/libQt5Network.so.5.5.1 differ diff --git a/camera_driver/lib/Qt/libQt5Xml.so.5.5.1 b/camera_driver/lib/Qt/libQt5Xml.so.5.5.1 new file mode 100644 index 0000000..f005c55 Binary files /dev/null and b/camera_driver/lib/Qt/libQt5Xml.so.5.5.1 differ diff --git a/camera_driver/lib/libImageConvert.so b/camera_driver/lib/libImageConvert.so new file mode 100644 index 0000000..bf3b972 Binary files /dev/null and b/camera_driver/lib/libImageConvert.so differ diff --git a/camera_driver/lib/libMVSDK.so.2.1.0.194984 b/camera_driver/lib/libMVSDK.so.2.1.0.194984 new file mode 100644 index 0000000..cc940a7 Binary files /dev/null and b/camera_driver/lib/libMVSDK.so.2.1.0.194984 differ diff --git a/camera_driver/lib/libMVSDKGuiQt.so b/camera_driver/lib/libMVSDKGuiQt.so new file mode 100644 index 0000000..79fb681 Binary files /dev/null and b/camera_driver/lib/libMVSDKGuiQt.so differ diff --git a/camera_driver/lib/libVideoRender.so b/camera_driver/lib/libVideoRender.so new file mode 100644 index 0000000..3cc9d67 Binary files /dev/null and b/camera_driver/lib/libVideoRender.so differ diff --git a/camera_driver/lib/liblog4cpp.so b/camera_driver/lib/liblog4cpp.so new file mode 100644 index 0000000..b4dfcd9 Binary files /dev/null and b/camera_driver/lib/liblog4cpp.so differ diff --git a/capture.py b/capture.py new file mode 100644 index 0000000..9c426bc --- /dev/null +++ b/capture.py @@ -0,0 +1,146 @@ +# -- coding: utf-8 -- +import time +import os +import paramiko +from scp import SCPClient +import threading +from os import abort + + +HOST = "192.168.100.254" +PORT = 22 +USERNAME = "root" +PASSWORD = "ebaina" + + +def ssh_execute_command(host, port, username, password, command): + ret = False + # 创建SSH客户端 + client = paramiko.SSHClient() + client.set_missing_host_key_policy(paramiko.AutoAddPolicy()) + client.connect(host, port, username, password) + + # 执行命令 + stdin, stdout, stderr = client.exec_command(command) + print(stdout.read().decode()) + print(stderr.read().decode()) + + # 关闭连接 + client.close() + return True + + +def scp_get_file(host, port, username, password, remote_path, local_path): + ret = False + # 创建SSH客户端 + client = paramiko.Transport((host, port)) + client.connect(username=username, password=password) + + # 创建SCP客户端 + scp_client = SCPClient(client) + + # 拉取文件 + try: + scp_client.get(remote_path, local_path) + except Exception as e: + print(e) + return False + + # 关闭连接 + scp_client.close() + client.close() + + return True + +def cameraCap(): + start_time = time.time() + ret = ssh_execute_command( + host = HOST, + port = PORT, + username = USERNAME, + password = PASSWORD, + command = "cd /root/calibration_tools \n" + + "./camera_driver 240000 \n" + ) + end_time = time.time() # 记录结束时间 + execution_time = end_time - start_time # 计算执行时间 + print(f"ssh_execute_command 程序执行时间:{execution_time}秒") + time.sleep(1) # 等待操作系统保存图像完毕 + ret = scp_get_file( + host = HOST, + port = PORT, + username = USERNAME, + password = PASSWORD, + remote_path = "/root/calibration_tools/output.png", + local_path = os.path.dirname(__file__) + "\\ssh_tmp\\1\\output.png" + ) + if not ret: + return False + ret = ssh_execute_command( + host = HOST, + port = PORT, + username = USERNAME, + password = PASSWORD, + command = "cd /root/calibration_tools \n " + + "rm output.png \n" + ) + end_time = time.time() # 记录结束时间 + execution_time = end_time - start_time # 计算执行时间 + print(f"cameraCap 程序执行时间:{execution_time}秒") + + +def lidarCap(): + start_time = time.time() + ret = ssh_execute_command( + host = HOST, + port = PORT, + username = USERNAME, + password = PASSWORD, + command = "cd /root/calibration_tools \n" + + "./lidar_driver \n" + ) + ret = scp_get_file( + host = HOST, + port = PORT, + username = USERNAME, + password = PASSWORD, + remote_path = "/root/calibration_tools/output.ply", + local_path = os.path.dirname(__file__) + ".\\ssh_tmp\\1\\output.ply" + ) + ret = ssh_execute_command( + host = HOST, + port = PORT, + username = USERNAME, + password = PASSWORD, + command = "cd /root/calibration_tools \n " + + "rm output.ply \n" + ) + end_time = time.time() # 记录结束时间 + execution_time = end_time - start_time # 计算执行时间 + print(f"lidarCap 程序执行时间:{execution_time}秒") + + +def cap(): + + directory = os.path.dirname(__file__) + ".\\ssh_tmp\\" + files_and_directories = os.listdir(directory) + for file in files_and_directories: + file_path = os.path.join(directory, file) + if os.path.isfile(file_path): + os.unlink(file_path) + + t_lidar = threading.Thread(target=lidarCap) + t_lidar.start() + cameraCap() + + # t_camera.join() + + t_lidar.join() + +if __name__ == '__main__': + # 1 设置条件 + # 2 cap + cap() + # 3 修改 config.ini + # 4 启动 image_framework.py + # 5 接收 回调,把结果保存下来 diff --git a/cloud_3d_detect.py b/cloud_3d_detect.py new file mode 100644 index 0000000..78fd6b7 --- /dev/null +++ b/cloud_3d_detect.py @@ -0,0 +1,1244 @@ +# -- coding: utf-8 -- +from ctypes import * +import cv2 # 4.9.0 +print(cv2.__version__) # 4.9.0 +import numpy as np +print(np.__version__) # 1.24.4 +import open3d as o3d +print(o3d.__version__) # 0.18.0 +import math +import os +import time +# from skimage import feature +import aurco_3d_detect as aurco_3d_detect +from os import abort +from utils import Log +from config import * + +# 点云整体移动 kk +# 边缘点散射后需要重新投影到平面 +# 顶点算法再优化 + +# 流程 +# 3D点云整理修正,kk参数(该参数与物体反射率相关,通过MAP映射,后期不断更新MAP内容) +# 3D点云空间过滤 +# 3D点云提取标定板 seg_mark_cloud + # 生成 im_2d_to_3d (采用相机内参) + # 生成 im_project (采用相机内参) + # 通过 im_project 识别标定板2D区域 obj_roi + # 将 im_2d_to_3d 中的3D点云数据按照 obj_roi 进行归集,形成单独的标定板的3D数据文件 +# 优化标定板3D数据 correct_mark_cloud + # 3D 数据平滑、游离点\噪点去除 + # 使用 RANSAC 平面拟合,计算平面模型 [A,B,C,D]、计算内点集合 inlier_cloud 、计算外点集合 outlier_cloud + # 最小二乘计算 inlier_cloud 拟合的平面 + # 通过平面模型 [A,B,C,D] 将内外点重投至该平面,计算 inlier_pcd_correct + # 将 inlier_pcd_correct 和 inlier_cloud 合并至 inlier_pcd_correct +# 3D标定板角点提取 select_conners_from_mark_cloud_2d + # 通过 select_conners_from_mark_cloud_3d 对 inlier_pcd_correct 自动选取 3D 角点 (3D角点自动提取算法) + # 将 inlier_pcd_correct 投影至 2D + # 生成 im_2d_to_3d_n (n:1-4)(采用相机内参) + # 生成 im_project_n (n:1-4) (采用相机内参) + # 在2D图中人工标记角点 + # 通过2D点、H、[A,B,C,D] 得到3D角点 c_lidar[16] + # 【check】通过3D角点 c_lidar[16] 计算得出的标定板边长 l 和实际值的误差(绝对误差、4条边的均方差) +# 2D标定板角点提取 + # 定位 ARUCO 标记,计算外参 + # 计算标定板4个角点的3D值 c_camera[16] + # 【check】通过3D角点 c_camera[16] 计算得出的标定板边长 l 和实际值的误差(绝对误差、4条边的均方差) +# SVD + # 使用SVD c_lidar[16] 和 c_camera[16] 计算相机和雷达的旋转矩阵 RT + # 循环采用不同数据通过SVD进行上述计算,采用最大似然优化 RT + # 【check】c_lidar[16] 通过 RT 恢复到的位置和 c_camera[16] 比较(绝对误差、4条边的均方差) + # 【check】3D点云通过重投影到2D图像的角点和标定板图像角点的误差估计(人工) +# 推理验证 + # 2D识别标定板 + # 2D标定板角点提取 + # 通过2D点、H、[A,B,C,D] 得到3D角点,c_lidar_camera[16] + # 【check】c_lidar_camera[16]、c_lidar[16] 的误差(绝对误差、4条边的均方差) + # 【check】c_lidar_camera[16]、c_camera[16] 、c_lidar[16]计算得出的边长和实际值的误差(绝对误差、4条边的均方差) +# 自动化参数优化 + # 实现自动推理验证流程 + # 生成参数和结果对照记录 + # 自动优化参数 +# 预埋件实测 + +def _eulerAnglesToRotationMatrix(theta) : + R_x = np.array([[1, 0, 0 ], + [0, math.cos(theta[0]), -math.sin(theta[0]) ], + [0, math.sin(theta[0]), math.cos(theta[0]) ] + ]) + R_y = np.array([[math.cos(theta[1]), 0, math.sin(theta[1]) ], + [0, 1, 0 ], + [-math.sin(theta[1]), 0, math.cos(theta[1]) ] + ]) + R_z = np.array([[math.cos(theta[2]), -math.sin(theta[2]), 0], + [math.sin(theta[2]), math.cos(theta[2]), 0], + [0, 0, 1] + ]) + R = np.dot(R_z, np.dot( R_y, R_x )) + return R + +def cal_project_matrix(): + # src_size是原始图像的大小 + src_size = (w, h) + + # 计算新的摄像机矩阵 + new_camera_matrix = cv2.getOptimalNewCameraMatrix(camera_matrix, dist_coeffs, src_size, alpha=0) + Log.info("2D 投影矩阵计算结果为:") + print(new_camera_matrix) + # print(new_camera_matrix) + return new_camera_matrix + + +# 定义获取点云深度最大最小值 +def get_pcd_depth_range(pts_3d): + # 初始化最小值和最大值为第一个点的x坐标 + min_x = 0 + max_x = 0 + + # 遍历所有点,更新最小值和最大值 + for point_3d in pts_3d.points: + x = point_3d[0] + if x < min_x: + min_x = x + elif x > max_x: + max_x = x + + return max_x, min_x + +def undistort(distorted_img): + # 矫正畸变 + undistorted_img = cv2.undistort(distorted_img, camera_matrix, dist_coeffs, None, camera_matrix) + # cv2.imwrite("distorted_img.png", undistorted_img) + # undistorted_img = cv2.imread("distorted_img.png") + # cv2.imshow("1", undistorted_img) + # cv2.waitKey(0) + return undistorted_img + +def clear_folder(folder_path): + for file_name in os.listdir(folder_path): + file_path = os.path.join(folder_path, file_name) + if os.path.isfile(file_path): + os.remove(file_path) + else: + clear_folder(file_path) + os.rmdir(file_path) + + +def sort_marks_pcd_3d(masks): + new_mask = [] + left_pt_0, left_pt_1, left_pt_2, left_pt_3 = 0,0,0,0 + delete_index = [] + coordinate_temp = [0,1,2,3] + max_val = 0 + min_val = 999999 + for i in range(4): + left_pt = masks[i][0] + val = left_pt[0] + left_pt[1] + if val > max_val: + left_pt_3 = i + max_val = val + if val < min_val: + left_pt_0 = i + min_val = val + delete_index.append(left_pt_0) + delete_index.append(left_pt_3) + coordinate_temp = np.delete(coordinate_temp, delete_index, axis=0) + if masks[coordinate_temp[0]][0][0] > masks[coordinate_temp[1]][0][0]: + left_pt_1 = coordinate_temp[0] + left_pt_2 = coordinate_temp[1] + else: + left_pt_2 = coordinate_temp[0] + left_pt_1 = coordinate_temp[1] + new_mask.append(masks[left_pt_0]) + new_mask.append(masks[left_pt_1]) + new_mask.append(masks[left_pt_2]) + new_mask.append(masks[left_pt_3]) + return new_mask + + +def detect_marks_roi(im_project, show=False): + masks = [] + + offset = 40 + kernel = cv2.getStructuringElement(cv2.MORPH_RECT, (30, 30)) + im_tmp = cv2.morphologyEx(im_project, cv2.MORPH_DILATE, kernel) + im_tmp = cv2.GaussianBlur(im_tmp, (29, 29), 0) + + # im_tmp = cv2.resize(im_tmp, (900, 700)) + # cv2.imshow(".",im_tmp) + # cv2.waitKey(0) + + # 查找联通区域 + gray = cv2.cvtColor(im_tmp, cv2.COLOR_BGR2GRAY) + _, binary = cv2.threshold(gray, 128, 255, cv2.THRESH_BINARY) + # num_labels, labels, stats, centroids = cv2.connectedComponentsWithStats(binary, connectivity=8, ltype=cv2.CV_32S) + + + contours, _ = cv2.findContours(binary, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE) + colors = [ (255, 0, 0) , (255, 255, 0) , (0, 0, 255) , (255, 0, 255) ] + color_idx = 0 + + Log.info("3D->2D 投影连通区域的像素点数量:") + for contour in contours: + rect_conner_points = [] + size = cv2.contourArea(contour) + top_idx = 0 + right_idx = 0 + bottom_idx = 0 + left_idx = 0 + x, y, w, h = cv2.boundingRect(contour) + for idx in range(len(contour)): + if y == contour[idx][0][1]: top_idx = idx + if x == contour[idx][0][0]: left_idx = idx + if y + h - 1 == contour[idx][0][1]: bottom_idx = idx + if x + w - 1 == contour[idx][0][0]: right_idx = idx + contour[left_idx][0][0] -= offset + contour[top_idx][0][1] -= offset + contour[right_idx][0][0] += offset + contour[bottom_idx][0][1] += offset + if contour[left_idx][0][0] < 0 or contour[top_idx][0][1] < 0 or \ + contour[right_idx][0][0] > global_w or contour[bottom_idx][0][1] > global_h: + continue + if size > rmin: + print(size) + if size > rmin and size < rmax: + contour[left_idx][0][0] -= offset + contour[top_idx][0][1] -= offset + contour[right_idx][0][0] += offset + contour[bottom_idx][0][1] += offset + cv2.circle(im_project, (contour[top_idx][0][0], contour[top_idx][0][1]), 25, colors[color_idx] , -1) + cv2.circle(im_project, (contour[right_idx][0][0], contour[right_idx][0][1]), 25, colors[color_idx], -1) + cv2.circle(im_project, (contour[bottom_idx][0][0], contour[bottom_idx][0][1]), 25, colors[color_idx], -1) + cv2.circle(im_project, (contour[left_idx][0][0], contour[left_idx][0][1]), 25, colors[color_idx], -1) + rect_conner_points.append(contour[left_idx][0]) + rect_conner_points.append(contour[top_idx][0]) + rect_conner_points.append(contour[right_idx][0]) + rect_conner_points.append(contour[bottom_idx][0]) + masks.append(rect_conner_points) + color_idx += 1 + + + if len(masks) != MARK_COUNT: + Log.error("3D 重投影未找到4个mark") + show = True + if show: + im_project = cv2.resize(im_project, (900, 700)) + cv2.imshow("im", im_project) + cv2.waitKey(0) + return [] + + # 按照 左上1,右上2,左下3,右下4的顺序重新排序 + masks = sort_marks_pcd_3d(masks) + + # for test + if show: + im_project = cv2.resize(im_project, (900, 700)) + cv2.imshow("im", im_project) + cv2.waitKey(0) + return masks + + +def project_cloud(pcd_cloud): + im_project = np.zeros((global_h, global_w, 3), dtype=np.uint8) + im_2d_to_3d = np.zeros((global_h ,global_w, 3), dtype=np.float64) + rvec = np.array([np.array([0.]), np.array([0.]), np.array([0.])]) + tvec = np.float64([0.0, 0.0, 0.0]) + pts_2d, _ = cv2.projectPoints(np.array(pcd_cloud.points), rvec, tvec, camera_matrix, dist_coeffs) + color = (255,255,255) + list_pts_2d = pts_2d.tolist() + list_pts_2d = [[[int(item) for item in subsublist] for subsublist in sublist] for sublist in list_pts_2d] + points_np = np.asarray(pcd_cloud.points) + for i, pt_2d in enumerate(list_pts_2d): + # x, y = pt_2d.ravel() + # if x == float('nan') or y == float('nan'): continue + # x, y = int(x), int(y) + # x, y = pt_2d[0][0], pt_2d[0][1] + if 0 <= pt_2d[0][0] < global_w and 0 <= pt_2d[0][1] < global_h: + im_project[pt_2d[0][1], pt_2d[0][0]] = color + # im_2d_to_3d[y, x][0] = pcd_cloud.points[i][0] + # im_2d_to_3d[y, x][1] = pcd_cloud.points[i][1] + # im_2d_to_3d[y, x][2] = pcd_cloud.points[i][2] + im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]] = points_np[i] + return im_project, im_2d_to_3d, pts_2d, list_pts_2d + +def seg_mark_cloud(ply_file_path, kk, show=False): + marks_pcd = [] + + src_cloud_load = o3d.io.read_point_cloud(ply_file_path) + if src_cloud_load is None or len(src_cloud_load.points) == 0 : + abort() + + start_time = time.time() + + # 点云旋转 + Rx = src_cloud_load.get_rotation_matrix_from_xyz((roll, 0, 0)) + Ry = src_cloud_load.get_rotation_matrix_from_xyz((0, pitch, 0)) + Rz = src_cloud_load.get_rotation_matrix_from_xyz((0, 0, yaw)) + # t_matrix = np.identity(4) + # t_matrix[:3, 3] = T_vector + src_cloud_load.rotate(Rx, (1,0,0)) + src_cloud_load.rotate(Ry, (0,1,0)) + src_cloud_load.rotate(Rz, (0,0,1)) + src_cloud_load.translate(T_vector) + + # 点云筛选 + project_inlier_cloud = o3d.geometry.PointCloud() + for point_3d in np.asarray(src_cloud_load.points): + if -2.0 < point_3d[0] < 2.0 and -2.0 < point_3d[1] < 2.0 and point_3d[2] < 3.5: # 筛选x,y,z坐标 + _r = math.sqrt(pow(point_3d[0], 2) + pow(point_3d[1], 2) + pow(point_3d[2], 2)) + if _r == 0: continue + if point_3d[0] > 0: point_3d[0] = point_3d[0] + point_3d[0] / _r * kk + else: point_3d[0] = point_3d[0] + point_3d[0] / _r * kk + if point_3d[1] > 0: point_3d[1] = point_3d[1] + point_3d[1] / _r * kk + else: point_3d[1] = point_3d[1] + point_3d[1] / _r * kk + point_3d[2] = point_3d[2] + point_3d[2] / _r * kk + # point_3d[2] -= 0.0 + project_inlier_cloud.points.append((point_3d[0], point_3d[1], point_3d[2])) + + # 投影3D点云 + im_project, im_2d_to_3d, pts_2d, list_pts_2d = project_cloud(project_inlier_cloud) + + # 自动识别ROI角点 + mark_rois = detect_marks_roi(im_project, show) + if len(mark_rois) != MARK_COUNT: + return marks_pcd + + # 保存4个点云的数据到文件 + # clear_folder("./detect_cloud") + clear_folder(conf_temp_cloud_path) + # list_pts_2d = pts_2d.tolist() + # list_pts_2d = [[[int(item) for item in subsublist] for subsublist in sublist] for sublist in list_pts_2d] + for i in range(len(mark_rois)): + if len(mark_rois[i]) < 4: continue + one_mark_pcd = o3d.geometry.PointCloud() + mark_rois_tmp = np.asarray(mark_rois[i]) + for _, pt_2d in enumerate(list_pts_2d): + # x, y = pt_2d.ravel() + # x, y = int(x), int(y) + # x, y = pt_2d[0][0], pt_2d[0][1] + if cv2.pointPolygonTest(mark_rois_tmp, (pt_2d[0][0],pt_2d[0][1]), False) >= 0: + one_mark_pcd.points.append((im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]][0], + im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]][1], + im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]][2])) + # o3d.io.write_point_cloud("./detect_cloud/" + str(i) + ".ply", tmp_cloud) + o3d.io.write_point_cloud(conf_temp_cloud_path + str(i) + ".ply", one_mark_pcd) + if show: + o3d.visualization.draw_geometries([one_mark_pcd], mesh_show_wireframe=True) + marks_pcd.append(one_mark_pcd) + + if show: + im_project = cv2.resize(im_project, (int(934), int(700)), interpolation=cv2.INTER_LINEAR) + cv2.imshow("im_project", im_project) + cv2.waitKey(0) + + end_time = time.time() + execution_time = end_time - start_time + Log.info("3D 分割点云数据耗时:") + print(execution_time * 1000) + return marks_pcd + +def filter_cloud(pcd): + # 获取点云中的点坐标 + points = np.asarray(pcd.points) + + # 定义 x, y, z 的范围 + x_min, x_max = -1.8, 1.8 + y_min, y_max = -1.5, 1.5 + z_min, z_max = 0.0, global_z_max + + # 创建布尔掩膜 + mask = ( + (points[:, 0] >= x_min) & (points[:, 0] <= x_max) & + (points[:, 1] >= y_min) & (points[:, 1] <= y_max) & + (points[:, 2] >= z_min) & (points[:, 2] <= z_max) + ) + + # 应用掩膜以过滤点云 + filtered_points = points[mask] + + # 更新点云对象 + pcd.points = o3d.utility.Vector3dVector(filtered_points) + return pcd + +def seg_mark_cloud_simple(ply_file_path, kk, show=False): + marks_pcd = [] + + src_cloud_load = o3d.io.read_point_cloud(ply_file_path) + if src_cloud_load is None or len(src_cloud_load.points) == 0 : + abort() + + start_time = time.time() + + # 点云旋转 + Rx = src_cloud_load.get_rotation_matrix_from_xyz((roll, 0, 0)) + Ry = src_cloud_load.get_rotation_matrix_from_xyz((0, pitch, 0)) + Rz = src_cloud_load.get_rotation_matrix_from_xyz((0, 0, yaw)) + # t_matrix = np.identity(4) + # t_matrix[:3, 3] = T_vector + src_cloud_load.rotate(Rx, (1,0,0)) + src_cloud_load.rotate(Ry, (0,1,0)) + src_cloud_load.rotate(Rz, (0,0,1)) + src_cloud_load.translate(T_vector) + + # 点云筛选 + project_inlier_cloud = o3d.geometry.PointCloud() + if kk != 0.0: + for point_3d in np.asarray(src_cloud_load.points): + if -2.0 < point_3d[0] < 2.0 and -2.0 < point_3d[1] < 2.0 and point_3d[2] < global_z_max: # 筛选x,y,z坐标 + _r = math.sqrt(pow(point_3d[0], 2) + pow(point_3d[1], 2) + pow(point_3d[2], 2)) + if _r == 0: continue + if point_3d[0] > 0: point_3d[0] = point_3d[0] + point_3d[0] / _r * kk + else: point_3d[0] = point_3d[0] + point_3d[0] / _r * kk + if point_3d[1] > 0: point_3d[1] = point_3d[1] + point_3d[1] / _r * kk + else: point_3d[1] = point_3d[1] + point_3d[1] / _r * kk + point_3d[2] = point_3d[2] + point_3d[2] / _r * kk + # point_3d[2] -= 0.0 + project_inlier_cloud.points.append((point_3d[0], point_3d[1], point_3d[2])) + else: + project_inlier_cloud = filter_cloud(src_cloud_load) + + # 投影3D点云 + im_project, im_2d_to_3d, pts_2d, list_pts_2d = project_cloud(project_inlier_cloud) + + # 自动识别ROI角点 + mark_rois = detect_marks_roi(im_project, show) + if len(mark_rois) != MARK_COUNT: + return marks_pcd + + # 保存4个点云的数据到文件 + # clear_folder("./detect_cloud") + # clear_folder(conf_temp_cloud_path) + # list_pts_2d = pts_2d.tolist() + # list_pts_2d = [[[int(item) for item in subsublist] for subsublist in sublist] for sublist in list_pts_2d] + Log.info("3D->2D project points") + for i in range(len(mark_rois)): + if len(mark_rois[i]) < 4: continue + one_mark_pcd = o3d.geometry.PointCloud() + mark_rois_tmp = np.asarray(mark_rois[i]) + select_itmes = 0 + for _, pt_2d in enumerate(list_pts_2d): + # x, y = pt_2d.ravel() + # x, y = int(x), int(y) + # x, y = pt_2d[0][0], pt_2d[0][1] + if cv2.pointPolygonTest(mark_rois_tmp, (pt_2d[0][0],pt_2d[0][1]), False) >= 0: + # one_mark_pcd.points.append((im_2d_to_3d[y, x][0], im_2d_to_3d[y, x][1], im_2d_to_3d[y, x][2])) + one_mark_pcd.points.append((im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]][0], + im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]][1], + im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]][2])) + select_itmes += 1 + print(select_itmes) + # o3d.io.write_point_cloud("./detect_cloud/" + str(i) + ".ply", tmp_cloud) + + # 不写入文件,节省时间 + # o3d.io.write_point_cloud(conf_temp_cloud_path + str(i) + ".ply", one_mark_pcd) + # if show: + # o3d.visualization.draw_geometries([one_mark_pcd], mesh_show_wireframe=True) + + marks_pcd.append(one_mark_pcd) + + if show: + im_project = cv2.resize(im_project, (int(934), int(700)), interpolation=cv2.INTER_LINEAR) + cv2.imshow("im_project", im_project) + cv2.waitKey(0) + + end_time = time.time() + execution_time = end_time - start_time + Log.info("3D 分割点云数据耗时:") + print(execution_time * 1000) + return marks_pcd + +# distance_threshold (float): +# 平面内点的最大距离阈值。这是指一个点到估计平面的距离,如果距离小于或等于这个阈值,则认为该点属于此平面。 +# ransac_n (int): +# 每次迭代中用于估计模型的点数。对于平面分割,通常设置为 3,因为三个非共线点可以唯一确定一个平面。 +# num_iterations (int): +# RANSAC 算法的迭代次数。更多的迭代次数会增加找到最优解的概率,但也增加了计算时间。 +def correct_mark_cloud(mark_pcd): + plane_model, inliers = mark_pcd.segment_plane(distance_threshold=0.0155, + ransac_n=3, + num_iterations=10000) + inlier_pcd = mark_pcd.select_by_index(inliers) + inlier_pcd = reproject_cloud(plane_model, inlier_pcd) #利用投影得到的图像 + inlier_pcd = inlier_pcd.paint_uniform_color([1.0, 0, 0]) + outlier_cloud = mark_pcd.select_by_index(inliers, invert=True) + + # 暂时没有用到 + # radius = 0.05 + # inlier_pcd = smooth_point_cloud(inlier_pcd, radius) #利用拟合得到的图像 + + inlier_pcd_correct = reproject_cloud(plane_model, mark_pcd) #利用投影得到的图像 + inlier_pcd_correct = inlier_pcd_correct.paint_uniform_color([0.0, 1.0, 0]) + # o3d.visualization.draw_geometries([ inlier_pcd, inlier_pcd_correct ]) + # inlier_pcd_correct = inlier_pcd # ??? + return plane_model, inlier_pcd, inlier_pcd_correct + + +# 3D标定板角点提取 select_conners_from_mark_cloud_2d + # 通过 select_conners_from_mark_cloud_3d 对 inlier_pcd_correct 自动选取 3D 角点 (3D角点自动提取算法) + # 将 inlier_pcd_correct 投影至 2D + # 生成 im_2d_to_3d_n (n:1-4)(采用相机内参) + # 生成 im_project_n (n:1-4) (采用相机内参) + # 在2D图中人工标记角点 + # 通过2D点、H、[A,B,C,D] 得到3D角点 c_lidar[16] + # 【check】通过3D角点 c_lidar[16] 计算得出的标定板边长 l 和实际值的误差(绝对误差、4条边的均方差) +def cal_H(im_2d_to_3d, pts_2d, list_pts_2d): + pts_3d = [] + # list_pts_2d = pts_2d.tolist() + # list_pts_2d = [[[int(item) for item in subsublist] for subsublist in sublist] for sublist in list_pts_2d] + for i, pt_2d in enumerate(list_pts_2d): + # x, y = pt_2d.ravel() + # x, y = int(x), int(y) + # x, y = pt_2d[0][0], pt_2d[0][1] + pts_3d.append([im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]][0], + im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]][1], + im_2d_to_3d[pt_2d[0][1], pt_2d[0][0]][2]]) + ransacReprojThreshold = 3.0 + # 查找单应矩阵 + # 修改第三个参数 1.0 -> 5.0 + # 利用基于RANSAC的鲁棒算法选择最优的四组配对点,再计算转换矩阵H(3*3)并返回,以便于反向投影错误率达到最小 + # ransacReprojThreshold 设置为 1.0 + # H, mask = cv2.findHomography(np.array(src_points), np.array(dst_points), cv2.RANSAC, ransacReprojThreshold, maxIters=1500, confidence=0.998) ## 修改 1.0 -> 5.0 + pts_hom = [] + for i in range(len(pts_2d)): + pt = pts_2d[i] + x,y = pt[0][0], pt[0][1] + pts_hom.append([x*1.0, y*1.0, 1.0]) + H, _ = cv2.findHomography(np.array(pts_3d), np.array(pts_hom), cv2.RANSAC, ransacReprojThreshold) ## 修改 1.0 -> 5.0 + Log.info("2D-3D 单应性矩阵计算结果为:") + print(H) + return H + +def sort_conners_2d(conners): + sort_conner = [] + left, top, right, bottom = 0, 0, 0, 0 + # maxx,maxy = 0,0 + maxx,maxy = -100000,-100000 + minx,miny = 100000,100000 + for i in range(len(conners)): + conner = conners[i] + if conner[0] < minx: + minx = conner[0] + left = i + if conner[0] > maxx: + maxx = conner[0] + right = i + if conner[1] < miny: + miny = conner[1] + top = i + if conner[1] > maxy: + maxy = conner[1] + bottom = i + sort_conner.append(conners[left]) + sort_conner.append(conners[top]) + sort_conner.append(conners[right]) + sort_conner.append(conners[bottom]) + return sort_conner + +def remove_convex_hull_points(contour): + hull = cv2.convexHull(contour, returnPoints=True) + hull_indices = set(hull.flatten()) + non_hull_points = [point for i, point in enumerate(contour) if i not in hull_indices] + return np.array(non_hull_points) + +def smooth_convex_hull(contour, epsilon=0.1): + # 计算凸包 + hull = cv2.convexHull(contour) + # 使用 approxPolyDP 减少顶点数量,从而达到平滑效果 + epsilon_value = epsilon * cv2.arcLength(hull, True) + smoothed_hull = cv2.approxPolyDP(hull, epsilon_value, True) + + return np.array(smoothed_hull) + +from scipy.interpolate import splprep, splev +def spline_fit(points, s=0, k=2): + # 确保有足够的数据点 + if len(points) <= k: + return None + + tck, u = splprep(points.T, s=s, k=k) + u_new = np.linspace(u.min(), u.max(), 1000) + x_new, y_new = splev(u_new, tck) + return np.vstack((x_new, y_new)).T + +def smooth_convex_hull_with_spline(contour, s=0): + hull = cv2.convexHull(contour) + points = hull.reshape(-1, 2) + smoothed_points = spline_fit(points, s=s) + if smoothed_points is None: + return None + return smoothed_points.astype(np.int32) + +def find_largest_contour(contours): + if not contours: + return None + + # 计算所有轮廓的面积 + areas = [cv2.contourArea(cnt) for cnt in contours] + + # 找到面积最大的轮廓索引 + max_area_index = np.argmax(areas) + + # 返回面积最大的轮廓 + return contours[max_area_index] + +from shapely.geometry import Polygon,MultiPolygon # 需要安装 shapely 库来处理多边形相交 +def rect_to_polygon(rect): + box = cv2.boxPoints(rect) + return Polygon(box) + +def polygon_intersection(poly1, poly2): + inter_poly = poly1.intersection(poly2) + if not inter_poly.is_empty: + return inter_poly + else: + return None + +def fill_intersection_white(image, rect1, rect2): + """ + 在给定图像中,用白色填充两个旋转矩形的相交区域。 + + 参数: + image (numpy.ndarray): 输入图像 + rect1 (tuple): 第一个旋转矩形,格式为 (center, size, angle) + rect2 (tuple): 第二个旋转矩形,格式为 (center, size, angle) + """ + # 将旋转矩形转换为多边形 + poly1 = rect_to_polygon(rect1) + poly2 = rect_to_polygon(rect2) + + # 计算相交区域 + intersection = polygon_intersection(poly1, poly2) + + if intersection is not None: + # 创建掩膜并填充白色 + mask = np.zeros_like(image) + + # 如果相交区域是多边形 + if isinstance(intersection, Polygon): + inter_points = np.array(intersection.exterior.coords, dtype=np.int32) + cv2.fillPoly(mask, [inter_points], (255, 255, 255)) + elif isinstance(intersection, MultiPolygon): + for geom in intersection.geoms: + inter_points = np.array(geom.exterior.coords, dtype=np.int32) + cv2.fillPoly(mask, [inter_points], (255, 255, 255)) + + # 应用掩膜到原图 + image[mask == 255] = 255 + + +def select_conners_from_mark_cloud_2d_old(mark_pcd, plane_model): + # 将 inlier_pcd_correct 投影至 2D + im_project, im_2d_to_3d, pts_2d, list_pts_2d = project_cloud(mark_pcd) + im_project_gray = cv2.cvtColor(im_project, cv2.COLOR_BGR2GRAY) + non_zero = cv2.findNonZero(im_project_gray) + + kernel = cv2.getStructuringElement(cv2.MORPH_RECT, (20, 20)) + im_project = cv2.morphologyEx(im_project, cv2.MORPH_DILATE, kernel) + + for point in non_zero: + im_project[point[0][1], point[0][0]] = (255,255,255) + rect = cv2.minAreaRect(non_zero) + box = cv2.boxPoints(rect) + box = np.int0(box) + # for test + # cv2.drawContours(im_project, [box], 0, (255), 10) + # im_project = cv2.resize(im_project, (1600, 1200)) + # cv2.imshow("_im", im_project) + # cv2.waitKey(0) + + # 计算 mark cloud 点云的单应矩阵 + H = cal_H(im_2d_to_3d, pts_2d, list_pts_2d) + + # 获取高精确的角点 2D 位置 + conners = sort_conners_2d(list(box)) + + # 通过单应矩阵计算角点 3D 位置 + H_inv = np.linalg.inv(H) + conners_pcd = o3d.geometry.PointCloud() + for i in range(4): + conner = conners[i] + x, y = conner[0], conner[1] + pts_hom = np.array([x, y, 1]) + pts_3d = np.dot(H_inv, pts_hom.T) + pts_3d = pts_3d/pts_3d[2] + conners_pcd.points.append((pts_3d[0],pts_3d[1],pts_3d[2])) + conners_pcd = reproject_cloud(plane_model, conners_pcd) + + Log.info("2D标记角点,得到得边长为:") + for i in range(4): + print(np.linalg.norm(conners_pcd.points[i] - conners_pcd.points[(i+1)%4])) + return conners_pcd + +def select_conners_from_mark_cloud_2d(mark_pcd, plane_model): + # 将 inlier_pcd_correct 投影至 2D + im_project, im_2d_to_3d, pts_2d, list_pts_2d = project_cloud(mark_pcd) + im_project_gray = cv2.cvtColor(im_project, cv2.COLOR_BGR2GRAY) + non_zero = cv2.findNonZero(im_project_gray) + + kernel = cv2.getStructuringElement(cv2.MORPH_RECT, (20, 20)) + im_project = cv2.morphologyEx(im_project, cv2.MORPH_DILATE, kernel) + + for point in non_zero: + im_project[point[0][1], point[0][0]] = (255,255,255) + rect = cv2.minAreaRect(non_zero) + box = cv2.boxPoints(rect) + box = np.int0(box) + + #================================================ + kernel = cv2.getStructuringElement(cv2.MORPH_RECT, (40, 40)) + im_project_gray = cv2.morphologyEx(im_project_gray, cv2.MORPH_DILATE, kernel) + kernel = cv2.getStructuringElement(cv2.MORPH_CROSS, (40, 40)) + im_project_gray = cv2.morphologyEx(im_project_gray, cv2.MORPH_CLOSE, kernel) + + # im_project_gray = cv2.resize(im_project_gray, (1600, 1200)) + # cv2.imshow("im_project_gray", im_project_gray) + # cv2.waitKey(0) + _, binary_img = cv2.threshold(im_project_gray, 0, 255, cv2.THRESH_BINARY) + contours, _ = cv2.findContours(binary_img, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_SIMPLE) + # 对每个轮廓进行处理 + # processed_contours = [remove_convex_hull_points(cnt) for cnt in contours] + processed_contours = [smooth_convex_hull(cnt) for cnt in contours] + contour = find_largest_contour(processed_contours) + rect2 = cv2.minAreaRect(contour) + box2 = cv2.boxPoints(rect2) + box2 = np.int0(box2) + # box = box2 + + temp_img = np.zeros((im_project_gray.shape[0], im_project_gray.shape[1], 1), dtype=np.uint8) + fill_intersection_white(temp_img, rect, rect2) + non_zero = cv2.findNonZero(temp_img) + rect3 = cv2.minAreaRect(non_zero) + box3 = cv2.boxPoints(rect3) + box3 = np.int0(box3) + + box = box2 + + # processed_contours = [] + # for cnt in contours: + # smoothed_hull = smooth_convex_hull_with_spline(cnt, s=0.0) + # if smoothed_hull is None: continue + # # cv2.polylines(drawing, [smoothed_hull], isClosed=True, color=(0, 255, 0), thickness=2) + # processed_contours.append(smoothed_hull) + # drawing = np.zeros_like(im_project) + # cv2.drawContours(drawing, processed_contours, -1, color=255, thickness=1) + # cv2.imshow("Processed Contours", drawing) + # cv2.waitKey(0) + # + # for test + # cv2.drawContours(im_project, [box2], 0, (255), 15) + # # cv2.drawContours(im_project, processed_contours, -1, color=(0,0,255), thickness=10) + # cv2.drawContours(im_project, [box3], 0, (0,255,0), 20) + # for point in non_zero: + # im_project[point[0][1], point[0][0]] = (255,255,255) + # im_project = cv2.resize(im_project, (1400, 1000)) + # cv2.imshow("_im", im_project) + # cv2.waitKey(0) + #================================================ + + # 计算 mark cloud 点云的单应矩阵 + H = cal_H(im_2d_to_3d, pts_2d, list_pts_2d) + + # 获取高精确的角点 2D 位置 + conners = sort_conners_2d(list(box)) + + Log.error("3d-2d 的边长") + print(np.linalg.norm(conners[0] - conners[1])) + print(np.linalg.norm(conners[1] - conners[2])) + print(np.linalg.norm(conners[2] - conners[3])) + print(np.linalg.norm(conners[3] - conners[0])) + + # 通过单应矩阵计算角点 3D 位置 + H_inv = np.linalg.inv(H) + conners_pcd = o3d.geometry.PointCloud() + for i in range(4): + conner = conners[i] + x, y = conner[0], conner[1] + pts_hom = np.array([x, y, 1]) + pts_3d = np.dot(H_inv, pts_hom.T) + pts_3d = pts_3d/pts_3d[2] + conners_pcd.points.append((pts_3d[0],pts_3d[1],pts_3d[2])) + conners_pcd = reproject_cloud(plane_model, conners_pcd) + + Log.info("2D标记角点,得到得边长为:") + for i in range(4): + print(np.linalg.norm(conners_pcd.points[i] - conners_pcd.points[(i+1)%4])) + return conners_pcd + +def extend_line_3d(pt1, pt2, distance): + """ + 计算 3D 空间两个点的延长线上的一个点 + 参数: + - point1: 第一个点的坐标 (x1, y1, z1),类型为列表或数组 + - point2: 第二个点的坐标 (x2, y2, z2),类型为列表或数组 + - distance: 从第二个点延长的距离 (正值表示延长方向,负值表示反向) + 返回: + - 延长线上的点坐标 (x, y, z),类型为数组 + """ + # 转换为 NumPy 数组 + point1 = np.array(pt1) + point2 = np.array(pt2) + # 计算方向向量 + direction = point2 - point1 + # 计算方向向量的单位向量 + direction_unit = direction / np.linalg.norm(direction) + # 延长线上的点 + extended_point = point2 + distance * direction_unit + return extended_point + +def correct_mask_conner(inlier_pcd_correct, pcd_conners_2d): + oriented_bounding_box = inlier_pcd_correct.get_axis_aligned_bounding_box() + center_point = oriented_bounding_box.get_center() + # 0.3536 + real_len = 0.3535534 + pcd_correct_conners = o3d.geometry.PointCloud() + for i in range(4): + error_len = np.linalg.norm(pcd_conners_2d.points[i] - center_point) - real_len + real_conner = extend_line_3d(center_point, pcd_conners_2d.points[i], -error_len) + pcd_correct_conners.points.append(real_conner) + # print("中心点距离:" + str(np.linalg.norm(pcd_conners_2d.points[i] - center_point) )) + # print(real_conner) + return pcd_correct_conners, center_point + +def fit_plane_least_squares(points): + # 计算中心点 + centroid = np.mean(points, axis=0) + + # 计算协方差矩阵 + cov_matrix = (points - centroid).T.dot(points - centroid) + + # 计算协方差矩阵的特征值和特征向量 + eigenvalues, eigenvectors = np.linalg.eigh(cov_matrix) + + # 最小特征值对应的特征向量就是平面的法向量 + normal = eigenvectors[:, np.argmin(eigenvalues)] + return centroid, normal + + +def smooth_point_cloud(pcd, radius): + # Create a new PointCloud object + smoothed_pcd = o3d.geometry.PointCloud() + smoothed_points = [] + + # Build KDTree for the input point cloud + kdtree = o3d.geometry.KDTreeFlann(pcd) + + # For each point, perform least squares plane fitting + for point in np.asarray(pcd.points): + # Find points within the radius + [k, idx, _] = kdtree.search_radius_vector_3d(point, radius) + if k < 3: + # If there are not enough points, skip + continue + + # Extract neighboring points + neighbors = np.asarray(pcd.points)[idx, :] + + # Use least squares to fit a plane + centroid, normal = fit_plane_least_squares(neighbors) + + # Project the point onto the fitted plane + point_to_centroid = point - centroid + distance = point_to_centroid.dot(normal) + smoothed_point = point - distance * normal + smoothed_points.append(smoothed_point) + + # Set the smoothed points + smoothed_pcd.points = o3d.utility.Vector3dVector(smoothed_points) + return smoothed_pcd + + +def reproject_cloud(plane_model, cloud_load): + reproject_pcd = o3d.geometry.PointCloud() + A,B,C,D = plane_model + for pts_3d in cloud_load.points: + # 求线与平面的交点 + t = -D / (A * pts_3d[0] + B * pts_3d[1] + C * pts_3d[2]) + # pts_3d = np.array([t * pts_3d[0], t * pts_3d[1], t * pts_3d[2]]) + reproject_pcd.points.append((t * pts_3d[0], t * pts_3d[1], t * pts_3d[2])) + return reproject_pcd + + +def o2t(o_pcd): + t_pcd = o3d.t.geometry.PointCloud() + t_pcd.point.positions = o3d.core.Tensor(np.asarray(o_pcd.points)) + t_pcd.point.colors = o3d.core.Tensor(np.asarray(o_pcd.colors)) + o_pcd.estimate_normals(search_param=o3d.geometry.KDTreeSearchParamHybrid(radius=0.1, max_nn=30)) + t_pcd.point.normals = o3d.core.Tensor(np.asarray(o_pcd.normals)) + return t_pcd + + +def t2o(t_pcd): + o_pcd = o3d.geometry.PointCloud() + o_pcd.points = o3d.utility.Vector3dVector(t_pcd.point.positions.numpy()) + # o_pcd.colors = o3d.utility.Vector3dVector(t_pcd.point.colors.numpy()) + return o_pcd + + +# def calculate_curvature(pcd): +# # 估计法线 +# pcd.estimate_normals(search_param=o3d.geometry.KDTreeSearchParamHybrid(radius=0.1, max_nn=30)) + +# # 计算曲率 +# curvatures = [] +# for i in range(len(pcd.points)): +# normal = np.array(pcd.normals[i]) +# k_neighbors = pcd.select_by_index(pcd.nearest_k_neighbor(i, 10)[1]) # 获取最近的10个邻居 +# neighbor_normals = np.array(k_neighbors.normals) +# curvature = np.mean(np.abs(neighbor_normals - normal)) # 简单地取平均绝对差作为曲率估计 +# curvatures.append(curvature) + +# return np.array(curvatures) + + +def calculate_curvature(pcd): + # 估计法线 + pcd.estimate_normals(search_param=o3d.geometry.KDTreeSearchParamHybrid(radius=0.1, max_nn=30)) + + # 构建KDTree + pcd_tree = o3d.geometry.KDTreeFlann(pcd) + + # 计算曲率 + curvatures = [] + for i in range(len(pcd.points)): + [k, idx, _] = pcd_tree.search_knn_vector_3d(pcd.points[i], 10) # 获取最近的10个邻居 + neighbor_normals = np.array([pcd.normals[j] for j in idx]) + normal = np.array(pcd.normals[i]) + curvature = np.mean(np.abs(neighbor_normals - normal)) # 简单地取平均绝对差作为曲率估计 + curvatures.append(curvature) + + return np.array(curvatures) + + +def select_conners_from_mark_cloud_3d(inlier_cloud): + # 2. 计算凸包以获取边界点 + hull, _ = inlier_cloud.compute_convex_hull() + hull_points = np.asarray(hull.vertices) + + # 3. 将凸包顶点转换为点云对象以便后续处理 + hull_pcd = o3d.geometry.PointCloud() + hull_pcd.points = o3d.utility.Vector3dVector(hull_points) + + # 4. 简单地假设凸包是近似方形,计算四边形的四个角点 + # 这里采用一种简化方法,即寻找距离最远的两个点对作为对角线端点 + distances = np.linalg.norm(hull_points[:, None] - hull_points, axis=2) + max_distance_indices = np.unravel_index(np.argmax(distances), distances.shape) + diagonal_points = [] + diagonal_points.append(hull_points[max_distance_indices[0]]) + diagonal_points.append(hull_points[max_distance_indices[1]]) + diagonal_points = np.asarray(diagonal_points) + # 找到剩余两个角点,它们应位于对角线两端点构成的直线上 + remaining_points = np.delete(hull_points, max_distance_indices, axis=0) + idx = [] + for i in range(len(remaining_points)): + pt = remaining_points[i] + if np.linalg.norm(pt - diagonal_points[0]) < 0.3 or np.linalg.norm(pt - diagonal_points[1]) < 0.3 : + idx.append(i) + remaining_points = np.delete(remaining_points, idx, axis=0) + distances = np.linalg.norm(remaining_points[:, None] - remaining_points, axis=2) + max_distance_indices = np.unravel_index(np.argmax(distances), distances.shape) + diagonal_points2 = [] + diagonal_points2.append(remaining_points[max_distance_indices[0]]) + diagonal_points2.append(remaining_points[max_distance_indices[1]]) + diagonal_points2 = np.asarray(diagonal_points2) + + corner_points = [diagonal_points[0], diagonal_points[1], + diagonal_points2[0], diagonal_points2[1]] + + Log.info("3D标记角点,得到得边长为:") + print(np.linalg.norm(diagonal_points[0] - diagonal_points2[0])) + print(np.linalg.norm(diagonal_points[0] - diagonal_points2[1])) + print(np.linalg.norm(diagonal_points[1] - diagonal_points2[0])) + print(np.linalg.norm(diagonal_points[1] - diagonal_points2[1])) + + # 5. 创建一个新的点云来表示角点,并可视化 + corner_pcd = o3d.geometry.PointCloud() + corner_pcd.points = o3d.utility.Vector3dVector(corner_points) + + corner_pcd.paint_uniform_color([1, 0, 0]) + return corner_pcd + +from sklearn.cluster import DBSCAN +import copy +import scipy +def select_conners_from_mark_cloud_3d_v2(inlier_cloud): + # 修正 + downsampled_inlier_cloud = copy.deepcopy(inlier_cloud) + for i in range(len(downsampled_inlier_cloud.points)): + if i % 2 == 0: + downsampled_inlier_cloud.points[i][0] += 0.0001 + # 估计法线 + downsampled_inlier_cloud.estimate_normals() + # 寻找边界点 + cl, ind = downsampled_inlier_cloud.remove_statistical_outlier(nb_neighbors=20, std_ratio=2.0) + boundary_points = downsampled_inlier_cloud.select_by_index(ind, invert=True) + # 将边界点转换为numpy数组 + points = np.asarray(boundary_points.points) + # 假设我们正在寻找的是矩形,我们可以尝试用凸包算法来找到最小包围四边形 + hull = scipy.spatial.ConvexHull(points) + # 凸包顶点索引 + hull_vertices = hull.vertices + # 如果凸包有4个顶点,那么这些可能是我们要找的角点 + if len(hull_vertices) == 4: + corner_points = points[hull_vertices] + else: + # 如果不是4个顶点,则需要进一步处理 + # 这里简化处理,直接返回凸包顶点作为角点 + corner_points = points[hull_vertices] + + + # for i in range(len(downsampled_inlier_cloud.points)): + # if i % 2 == 0: + # downsampled_inlier_cloud.points[i][0] += 0.0001 + # obb = downsampled_inlier_cloud.get_oriented_bounding_box() + + # 提取角点 + # corner_points = np.asarray(obb.get_box_points()) + + # 创建新的点云对象表示角点 + corner_pcd = o3d.geometry.PointCloud() + corner_pcd.points = o3d.utility.Vector3dVector(corner_points) + + # 可视化结果 + o3d.visualization.draw_geometries([inlier_cloud, corner_pcd]) + + # corner_points = [diagonal_points[0], diagonal_points[1], + # diagonal_points2[0], diagonal_points2[1]] + + # Log.info("3D标记角点,得到得边长为:") + # print(np.linalg.norm(diagonal_points[0] - diagonal_points2[0])) + # print(np.linalg.norm(diagonal_points[0] - diagonal_points2[1])) + # print(np.linalg.norm(diagonal_points[1] - diagonal_points2[0])) + # print(np.linalg.norm(diagonal_points[1] - diagonal_points2[1])) + + # 5. 创建一个新的点云来表示角点,并可视化 + # corner_pcd = o3d.geometry.PointCloud() + # corner_pcd.points = o3d.utility.Vector3dVector(corner_points) + + # corner_pcd.paint_uniform_color([1, 0, 0]) + return corner_pcd + + +def create_spheres(points, sizes=None, color=[0, 0.706, 1]): + """ + 创建一系列球体以替代点云中的点,允许每个点有不同的大小。 + + 参数: + points: N x 3 数组,表示N个点的位置。 + sizes: N维数组或列表,表示对应点的半径大小。如果为None,则所有球体大小相同。 + color: RGB颜色值,默认是橙色。 + + 返回: + spheres: 包含所有球体的Open3D几何对象列表。 + """ + spheres = [] + if sizes is None: + sizes = [1] * len(points) # 如果没有提供大小,则默认所有球体大小相同 + for i, point in enumerate(points): + sphere = o3d.geometry.TriangleMesh.create_sphere(radius=sizes[i]) + sphere.translate(point) # 将球体移动到点的位置 + sphere.paint_uniform_color(color) + spheres.append(sphere) + return spheres + + +def cal_marks_3d_conners(show=False): + marks_3d_conners = [] + for i in range(4): + # mark_ply_file_path = './detect_cloud/' + str(i) + '.ply' + mark_ply_file_path = conf_temp_cloud_path + str(i) + '.ply' + + # 计算标定板尺寸 + # mark_ply_file_path = './detect_cloud/1.ply' + mark_pcd = o3d.io.read_point_cloud(mark_ply_file_path) + plane_model, inlier_cloud, inlier_pcd_correct = correct_mark_cloud(mark_pcd) + + # t_pcd = o2t(inlier_cloud) + # _dir = dir(t_pcd) + # for it in _dir: + # print(it) + # t_boundaries, mask = t_pcd.compute_boundary_points(0.05, 60) + # boundaries = t2o(t_boundaries) + + # # 计算曲率 + # curvatures = calculate_curvature(inlier_cloud) + # threshold = np.percentile(curvatures, 95) # 使用95百分位数作为阈值 + # corner_indices = np.where(curvatures > threshold)[0] + # t_corner_pcd = inlier_cloud.select_by_index(corner_indices.tolist()) + # t_corner_pcd.paint_uniform_color([0, 0, 1]) # 将角点涂成红色 + + used_pcd = inlier_cloud # inlier_cloud / inlier_pcd_correct + pcd_conners_2d = select_conners_from_mark_cloud_2d(used_pcd, plane_model) + pcd_conners_2d_correct, center_point = correct_mask_conner(used_pcd, pcd_conners_2d) + Log.info("修正后2D标记角点,得到得边长为:") + for i in range(4): + print(np.linalg.norm(pcd_conners_2d_correct.points[i] - pcd_conners_2d_correct.points[(i+1)%4])) + # pcd_conners_3d = select_conners_from_mark_cloud_3d(inlier_pcd_correct) + marks_3d_conners.append(pcd_conners_2d) + + if show: + # 角点显示的圆球半径,单位(米) + r = 0.006 + sizes = [r,r,r,r] + spheres_2d = create_spheres(pcd_conners_2d.points, sizes, color=[0, 0.706, 1]) + spheres_3d = create_spheres(pcd_conners_2d_correct.points, sizes, color=[0, 0, 0]) + spheres_center_3d = create_spheres([center_point], [0.01], color=[0, 1, 1]) + o3d.visualization.draw_geometries([ + spheres_2d[0],spheres_2d[1],spheres_2d[2],spheres_2d[3], + spheres_3d[0],spheres_3d[1],spheres_3d[2],spheres_3d[3], + spheres_center_3d[0], + mark_pcd.paint_uniform_color([1, 0, 0]), + inlier_pcd_correct.paint_uniform_color([0, 1, 0]),]) + + # mark 顺序按照 左上,右上,左下,右下 + # 每个mark的角点按照左、上、右、底顺序返回 + return marks_3d_conners + +def cal_marks_3d_conners_simple(marks_pcd_4, show=False): + marks_3d_conners = [] + for i in range(4): + # mark_ply_file_path = './detect_cloud/' + str(i) + '.ply' + mark_ply_file_path = conf_temp_cloud_path + str(i) + '.ply' + + # 计算标定板尺寸 + # mark_ply_file_path = './detect_cloud/1.ply' + # 不从文件读取 + # mark_pcd = o3d.io.read_point_cloud(mark_ply_file_path) + mark_pcd = marks_pcd_4[i] + plane_model, inlier_cloud, inlier_pcd_correct = correct_mark_cloud(mark_pcd) + + # t_pcd = o2t(inlier_cloud) + # _dir = dir(t_pcd) + # for it in _dir: + # print(it) + # t_boundaries, mask = t_pcd.compute_boundary_points(0.05, 60) + # boundaries = t2o(t_boundaries) + + # # 计算曲率 + # curvatures = calculate_curvature(inlier_cloud) + # threshold = np.percentile(curvatures, 95) # 使用95百分位数作为阈值 + # corner_indices = np.where(curvatures > threshold)[0] + # t_corner_pcd = inlier_cloud.select_by_index(corner_indices.tolist()) + # t_corner_pcd.paint_uniform_color([0, 0, 1]) # 将角点涂成红色 + + used_pcd = inlier_cloud # inlier_cloud / inlier_pcd_correct + # inlier_cloud -> box + # inlier_pcd_correct -> box2\box3 + pcd_conners_2d = select_conners_from_mark_cloud_2d(used_pcd, plane_model) + pcd_conners_2d_correct, center_point = correct_mask_conner(used_pcd, pcd_conners_2d) + Log.info("修正后2D标记角点,得到得边长为:") + for i in range(4): + print(np.linalg.norm(pcd_conners_2d_correct.points[i] - pcd_conners_2d_correct.points[(i+1)%4])) + # pcd_conners_3d = select_conners_from_mark_cloud_3d(inlier_pcd_correct) + marks_3d_conners.append(pcd_conners_2d_correct) # pcd_conners_2d / pcd_conners_2d_correct + + + # print(marks_3d_conners[0].points) + # print(marks_3d_conners[0].points[0]) + # print(np.linalg.norm(marks_3d_conners[0].points[0] - marks_3d_conners[0].points[1])) + # print(np.linalg.norm(marks_3d_conners[0].points[1] - marks_3d_conners[0].points[2])) + # print(np.linalg.norm(marks_3d_conners[0].points[2] - marks_3d_conners[0].points[3])) + # print(np.linalg.norm(marks_3d_conners[0].points[3] - marks_3d_conners[0].points[0])) + # Log.info("3D->3D 通过相邻角点计算得到的边长进行对比") + if show: + # 角点显示的圆球半径,单位(米) + r = 0.006 + sizes = [r,r,r,r] + spheres_2d = create_spheres(pcd_conners_2d.points, sizes, color=[0, 0.706, 1]) + spheres_3d = create_spheres(pcd_conners_2d_correct.points, sizes, color=[0, 0, 0]) + spheres_center_3d = create_spheres([center_point], [0.01], color=[0, 1, 1]) + o3d.visualization.draw_geometries([ + spheres_2d[0],spheres_2d[1],spheres_2d[2],spheres_2d[3], + spheres_3d[0],spheres_3d[1],spheres_3d[2],spheres_3d[3], + spheres_center_3d[0], + mark_pcd.paint_uniform_color([1, 0, 0]), + inlier_pcd_correct.paint_uniform_color([0, 1, 0]),]) + + # mark 顺序按照 左上,右上,左下,右下 + # 每个mark的角点按照左、上、右、底顺序返回 + return marks_3d_conners + +def print_diff(aurco_pt1, aurco_pt2, lidar_pt1, lidar_pt2): + aurco_distance = np.linalg.norm(aurco_pt1 - aurco_pt2) + lidar_distance = np.linalg.norm(lidar_pt1 - lidar_pt2) + print(aurco_distance) + print(lidar_distance) + print(abs(aurco_distance - lidar_distance)) + + +# 测试2d角点分割算法 +def _test_select_conners_from_mark_cloud_2d_2(): + pass + + +if __name__ == '__main__': + marks_3d_conners = [] + ply_file_path = os.path.dirname(__file__) + "\\samples\\calibration\\11\\output.ply" + marks_pcd = seg_mark_cloud_simple(ply_file_path, kk) + for i in range(4): + mark_ply_file_path = conf_temp_cloud_path + str(i) + '.ply' + mark_pcd = o3d.io.read_point_cloud(mark_ply_file_path) + plane_model, inlier_cloud, inlier_pcd_correct = correct_mark_cloud(mark_pcd) + # pcd_conners_2d = select_conners_from_mark_cloud_2d(mark_pcd, plane_model) + pcd_conners_2d = select_conners_from_mark_cloud_3d_v2(inlier_pcd_correct) + + + # image_project = cv2.imread("../caowei/new/output.png") + # # if image_project is None: + # # print("image_project is None!") + # # exit() + + # # # 分割标定板 + # ply_file_path = '../caowei/new/20241227175529496.ply' + + # marks_pcd = seg_mark_cloud(ply_file_path, kk) + # if len(marks_pcd) != MARK_COUNT: + # exit() + + # LEFT = 0 + # TOP = 1 + # RIGHT = 2 + # BOTTOM = 3 + + # frame, marks_aurco = aurco_3d_detect.cal_marks_3d_conners("../caowei/new/output.png") + + # marks_pcd = cal_marks_3d_conners() + # marks_pcd_new = [] + # # marks_pcd_new.append(marks_pcd[2].points) + # # marks_pcd_new.append(marks_pcd[3].points) + # # marks_pcd_new.append(marks_pcd[1].points) + # # marks_pcd_new.append(marks_pcd[0].points) + + # tmmp = [] + # for i in range(4): + # tmmp.append(marks_pcd[2].points[i]) + # marks_pcd_new.append(tmmp) + # tmmp = [] + # for i in range(4): + # tmmp.append(marks_pcd[3].points[i]) + # marks_pcd_new.append(tmmp) + # tmmp = [] + # for i in range(4): + # tmmp.append(marks_pcd[1].points[i]) + # marks_pcd_new.append(tmmp) + # tmmp = [] + # for i in range(4): + # tmmp.append(marks_pcd[0].points[i]) + # marks_pcd_new.append(tmmp) + + # print("======== 0 left - 1 right =========") + # print_diff(marks_aurco[0][LEFT] , marks_aurco[1][RIGHT], marks_pcd_new[0][LEFT], marks_pcd_new[1][RIGHT]) + # print("======== 0 left - 2 right =========") + # print_diff(marks_aurco[0][LEFT] , marks_aurco[2][RIGHT], marks_pcd_new[0][LEFT], marks_pcd_new[2][RIGHT]) + # print("======== 0 left - 3 right =========") + # print_diff(marks_aurco[0][LEFT] , marks_aurco[3][RIGHT], marks_pcd_new[0][LEFT], marks_pcd_new[3][RIGHT]) + # print("======== 0 right - 1 left =========") + # print_diff(marks_aurco[0][RIGHT] , marks_aurco[1][LEFT], marks_pcd_new[0][RIGHT] , marks_pcd_new[1][LEFT]) + # print("======== 0 top - 3 bottom =========") + # print_diff(marks_aurco[0][TOP] , marks_aurco[3][BOTTOM], marks_pcd_new[0][TOP] , marks_pcd_new[3][BOTTOM]) + # print("======== 2 left - 1 right =========") + # print_diff(marks_aurco[2][LEFT] , marks_aurco[1][RIGHT], marks_pcd_new[2][LEFT] , marks_pcd_new[1][RIGHT]) + # print("======== 2 left - 3 right =========") + # print_diff(marks_aurco[2][LEFT] , marks_aurco[3][RIGHT], marks_pcd_new[2][LEFT] , marks_pcd_new[3][RIGHT]) + + # exit() \ No newline at end of file diff --git a/config.py b/config.py new file mode 100644 index 0000000..4a0b171 --- /dev/null +++ b/config.py @@ -0,0 +1,73 @@ +import numpy as np +import os + +GLOBAL_WIDTH = 9344 +GLOBAL_HEIGH = 7000 + +# 相机内参矩阵,这里假设为简单的相机参数 +global_w = GLOBAL_WIDTH +global_h = GLOBAL_HEIGH + +MARK_COUNT = 4 + +# 相机内参 +conf_fx = 1.15504192e+04 +conf_fy = 1.15468773e+04 +conf_cx = 4.67228001e+03 +conf_cy = 3.49929103e+03 + +# 相机畸变参数 +conf_k1 = -1.98130409e-02 +conf_k2 = 4.46498961e-02 +conf_p1 = 3.32909840e-04 +conf_p2 = -4.24586368e-04 +conf_k3 = 3.71045956e-01 + +# conf_fx = 11241.983 +# conf_fy = 11244.0599 +# conf_cx = 4553.03821 +# conf_cy = 3516.9118 + +# conf_k1 = -0.04052072 +# conf_k2 = 0.22211572 +# conf_p1 = 0.00042405 +# conf_p2 = -0.00367346 +# conf_k3 = -0.15639485 + +# 相机内参矩阵 +camera_matrix = np.array([ + [conf_fx, 0, conf_cx], + [0, conf_fy, conf_cy], + [0, 0, 1]]) + +# 相机畸变矩阵 +# dist_coeffs = np.array([k1, k2, p1, p2]) +dist_coeffs = np.array([conf_k1, conf_k2, conf_p1, conf_p2, conf_k3]) + +T_vector = np.array([0.0, 0.0, 0.0]) # 初始化平移向量 +# roll, pitch, yaw = 0.0, -1.5707963, 1.5707963 # 初始化旋转角 对应(x,y,z) +roll, pitch, yaw = 1.587794314984622, -1.5573540052770616, 0.01084704933694234 # 0.0034 +roll, pitch, yaw = 1.5707963 , -1.5707963, 0.0 # 初始化旋转角 对应(x,y,z) +# roll,pitch,yaw = 1.5734601389822613, -1.556857147594011, 0.025063428135289487 + +# z 轴过滤 +global_z_max = 3.5 + +# aruco 板尺寸定义 +board_size = 0.5 +marker_size = 0.35 +b1 = 0.05 +b2 = 0.05 + +# 雷达数据修正系数 +kk = -0.01 +kk = 0.0 + +# 2D投影区域选择系数 +rmin = 3000000 +rmax = 20000000 + +# 16点中最多过滤的点数 +conf_max_exclude_num = 0 + +conf_temp_cloud_path = os.path.dirname(__file__) + "\\temp_cloud_data\\" \ No newline at end of file diff --git a/dialog-analysis.log b/dialog-analysis.log new file mode 100644 index 0000000..e69de29 diff --git a/it.py b/it.py new file mode 100644 index 0000000..2e01453 --- /dev/null +++ b/it.py @@ -0,0 +1,202 @@ +import numpy as np +from scipy.spatial.transform import Rotation as R +from scipy.linalg import svd +import os +import utils +import config + +def rotation_matrix_to_rpy(R): + # 确保输入是一个有效的旋转矩阵 + if not np.allclose(np.dot(R, R.T), np.eye(3)) or not np.isclose(np.linalg.det(R), 1.0): + raise ValueError("输入不是一个有效的旋转矩阵") + + _pitch = -np.arcsin(R[2, 0]) + + if np.abs(_pitch - np.pi / 2) < 1e-6: # 处理接近90度的情况 + _yaw = 0 + _roll = np.arctan2(R[0, 1], R[0, 2]) + elif np.abs(_pitch + np.pi / 2) < 1e-6: # 处理接近-90度的情况 + _yaw = 0 + _roll = -np.arctan2(R[0, 1], R[0, 2]) + else: + _yaw = np.arctan2(R[1, 0], R[0, 0]) + _roll = np.arctan2(R[2, 1], R[2, 2]) + + return _roll, _pitch, _yaw + +def average_rotation_matrices(rotation_matrices, weights=None): + # 将旋转矩阵转换为四元数 + quaternions = [R.from_matrix(matrix).as_quat() for matrix in rotation_matrices] + + if weights is None: + # 如果没有提供权重,则使用等权重 + weights = np.ones(len(quaternions)) / len(quaternions) + else: + # 确保权重之和为1 + weights = np.array(weights) / np.sum(weights) + + # 对四元数进行加权平均 + avg_quaternion = np.zeros(4) + for quat, weight in zip(quaternions, weights): + avg_quaternion += weight * quat + + # 归一化四元数以确保它是单位四元数 + avg_quaternion /= np.linalg.norm(avg_quaternion) + + # 将平均后的四元数转换回旋转矩阵 + avg_rotation_matrix = R.from_quat(avg_quaternion).as_matrix() + + return avg_rotation_matrix + +def addQ(q1, q2): + return np.quaternion(q1.x + q2.x, q1.y + q2.y, q1.z + q2.z, q1.w + q2.w) + +def calc_RT(lidar, camera, MAX_ITERS, lidarToCamera): + global iteration_counter, pkg_loc, translation_sum, rotation_sum, rotation_avg_by_mult, rmse_avg + + if iteration_counter == 0: + with open(pkg_loc + "/log/avg_values.txt", "w") as clean_file: + pass + + translation_sum = np.zeros((3, 1), dtype=float) + rotation_sum = np.ones(4) + rotation_avg_by_mult = np.eye(3, dtype=float) + rmse_avg = np.ones(3) + + num_points = lidar.shape[1] + print("Number of points:", num_points) + + mu_lidar = np.mean(lidar, axis=0) + mu_camera = np.mean(camera, axis=0) + + if iteration_counter == 0: + print("mu_lidar:\n", mu_lidar) + print("mu_camera:\n", mu_camera) + + # lidar_centered = lidar - mu_lidar[:, np.newaxis] + # camera_centered = camera - mu_camera[:, np.newaxis] + lidar_centered = lidar - mu_lidar + camera_centered = camera - mu_camera + + if iteration_counter == 0: + print("lidar_centered:\n", lidar_centered) + print("camera_centered:\n", camera_centered) + + # cov = camera_centered @ lidar_centered.T ERROR + H = np.dot(lidar_centered.T, camera_centered) + print(H) + + U, _, Vt = np.linalg.svd(H) + + # rotation = U @ Vt ERROR + rotation = np.dot(Vt, U.T) + + if np.linalg.det(rotation) < 0: + # rotation = U @ np.diag([1, 1, -1]) @ Vt + rotation = np.dot(Vt, U.T) + + # translation = mu_camera - rotation @ mu_lidar + translation = mu_camera.reshape(3, 1) - np.dot(rotation, mu_lidar.reshape(3, 1)) + + # averaging translation and rotation + translation_sum += translation + temp_q = R.from_matrix(rotation).as_quat() + if iteration_counter == 0: + rotation_sum = temp_q + else: + rotation_sum = rotation_sum + temp_q + + # averaging rotations by multiplication + if iteration_counter == 0: + rotation_avg_by_mult = rotation + else: + rotation_avg_by_mult = average_rotation_matrices([rotation_avg_by_mult, rotation]) + + # ea = R.from_matrix(rotation).as_euler('zyx') + ea = R.from_matrix(rotation).as_euler('xyz', degrees=False) + combine_ea = utils.combine_rpy(config.roll, config.pitch, config.yaw, ea[0], ea[1], ea[2]) + + print("Rotation matrix:\n", rotation) + print("Rotation in Euler :\n", ea) + print("Combin Rotation in Euler :\n", combine_ea) + print("Translation:\n", translation) + + # eltwise_error = np.sum((camera - (rotation @ lidar + translation[:, np.newaxis])) ** 2, axis=0) ERROR + eltwise_error = np.sum((camera - (np.dot(lidar, rotation) + translation[:, np.newaxis])) ** 2, axis=0) + error = np.sqrt(np.mean(eltwise_error)) + print("RMSE:", error) + + rmse_avg += error + + T = np.eye(4) + T[:3, :3] = rotation + T[:3, 3] = np.squeeze(translation) + + print("Rigid-body transformation:\n", T) + + iteration_counter += 1 + if iteration_counter % 1 == 0: + with open(pkg_loc + "/log/avg_values.txt", "a") as log_avg_values: + print("--------------------------------------------------------------------") + print(f"After {iteration_counter} iterations") + print("--------------------------------------------------------------------") + + print("Average translation is:\n", translation_sum / iteration_counter) + log_avg_values.write(f"{iteration_counter}\n") + log_avg_values.write(str(translation_sum / iteration_counter) + "\n") + + # rotation_sum_normalized = np.array([getattr(rotation_sum, dim) for dim in ['x', 'y', 'z', 'w']]) / iteration_counter + rotation_sum_normalized = rotation_sum / iteration_counter + mag = np.linalg.norm(rotation_sum_normalized) + rotation_sum_normalized /= mag + + rotation_avg = R.from_quat(rotation_sum_normalized).as_matrix() + print("Average rotation is:\n", rotation_avg) + # final_rotation = rotation_avg @ lidarToCamera ERROR + final_rotation = np.dot(lidarToCamera, rotation_avg) + + final_angles = R.from_matrix(final_rotation).as_euler('xyz') + combine_final_angles = utils.combine_rpy(config.roll, config.pitch, config.yaw, \ + final_angles[0], final_angles[1], final_angles[2]) + + log_avg_values.write("{:.8f} {:.8f} {:.8f}\n".format(*rotation_avg[0])) + log_avg_values.write("{:.8f} {:.8f} {:.8f}\n".format(*rotation_avg[1])) + log_avg_values.write("{:.8f} {:.8f} {:.8f}\n".format(*rotation_avg[2])) + + T_avg = np.eye(4) + T_avg[:3, :3] = rotation_avg + T_avg[:3, 3] = np.squeeze(translation_sum / iteration_counter) + print("Average transformation is:\n", T_avg) + print("Final rotation is:\n", final_rotation) + + print("Final ypr is:\n", final_angles) + print("Final Combine ypr is:\n", combine_final_angles) + print(f"Average RMSE is: {rmse_avg / iteration_counter}") + + # eltwise_error_temp = np.sum((camera - (rotation_avg @ lidar + (translation_sum / iteration_counter)[:, np.newaxis])) ** 2, axis=0) + eltwise_error_temp = np.sum((camera - (np.dot(lidar, rotation_avg) + (translation_sum / iteration_counter)[:, np.newaxis])) ** 2, axis=0) + + error_temp = np.sqrt(np.mean(eltwise_error_temp)) + print(f"RMSE on average transformation is: {error_temp}") + log_avg_values.write("{:.8f}\n".format(error_temp)) + + return T + + + +# Global variables initialization +iteration_counter = 0 +pkg_loc = "./record" +translation_sum = np.zeros((3, 1), dtype=float) +rotation_sum = np.ones(4) +rotation_avg_by_mult = np.eye(3, dtype=float) +rmse_avg = np.ones(3) + +if __name__ == "__main__": + all_points = utils.read_from_json(os.path.dirname(__file__) + '\\record\\points2.json') + # records = utils.read_from_json(os.path.dirname(__file__) + '\\record\\record.json') + carmera = np.asarray(all_points[0]) + lidar = np.asarray(all_points[1]) + lidarToCamera = R.from_euler('xyz', [config.roll, config.pitch, config.yaw], degrees=False).as_matrix() + + calc_RT(lidar, carmera, 50, lidarToCamera) \ No newline at end of file diff --git a/lidar_driver/CMakeLists.txt b/lidar_driver/CMakeLists.txt new file mode 100644 index 0000000..066ad63 --- /dev/null +++ b/lidar_driver/CMakeLists.txt @@ -0,0 +1,56 @@ +cmake_minimum_required(VERSION 3.24) + +include(${CMAKE_SOURCE_DIR}/cmake/cmakebase.cmake) +include(${CMAKE_SOURCE_DIR}/cmake/project.cmake) +include(${CMAKE_SOURCE_DIR}/cmake/ss928.cmake) + +PROJECT(lidar_driver) + +set(CMAKE_CXX_STANDARD 14) # 设置使用C++11标准 +set(CMAKE_CXX_STANDARD_REQUIRED ON) # 确保编译器遵循C++11标准 + +set(CMAKE_SOURCE_DIR "./") + +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fpermissive") + +set(OPENGL_opengl_LIBRARY /usr/lib/aarch64-linux-gnu/libOpenGL.so) +set(OPENGL_glx_LIBRARY /usr/lib/aarch64-linux-gnu/libGLX.so) +set(X11_X11_LIB /usr/lib/aarch64-linux-gnu/libX11.so) +find_package(Open3D REQUIRED) +if(NOT Open3D_FOUND) + message(FATAL_ERROR "Open3D not found.") +endif() +MESSAGE(${Open3D_VERSION}) +message(STATUS "Open3D include dirs: ${Open3D_INCLUDE_DIRS}") +message(STATUS "Open3D library dirs: ${Open3D_LIBRARY_DIRS}") +message(STATUS "Open3D libraries: ${Open3D_LIBRARIES}") + +include_directories( + /usr/local/include + ${CMAKE_SOURCE_DIR}/include/open3d/ + ${CMAKE_SOURCE_DIR}/include/ + ${CMAKE_SOURCE_DIR}/include/open3d/ + ${CMAKE_SOURCE_DIR}/include/open3d/3rdparty/ + ${CMAKE_SOURCE_DIR}/include/eigen3/ + ${CMAKE_SOURCE_DIR}/include/Livox/ +) + +link_directories( + /usr/local/lib + /usr/lib/aarch64-linux-gnu +) + +aux_source_directory(${CMAKE_SOURCE_DIR}/ CORE_LIST) +add_executable(${PROJECT_NAME} ${CORE_LIST}) + +set_target_properties(${PROJECT_NAME} PROPERTIES LINK_FLAGS "-Wl,-rpath-link,/usr/lib/aarch64-linux-gnu") +target_link_libraries( + ${PROJECT_NAME} + ${SYSTEM_LINK_LIB} + livox_sdk_static + pthread + dl + Open3D::Open3D +) + + diff --git a/lidar_driver/README.MD b/lidar_driver/README.MD new file mode 100644 index 0000000..2b42bb4 --- /dev/null +++ b/lidar_driver/README.MD @@ -0,0 +1,30 @@ +找到 CMakeLists.txt 中编译静态库的地方,确保添加 -fPIC 标志。可以通过以下方式添加: +```cmake +set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fPIC") +``` + +# source file +livox_sdk_wrapper.cpp + +# cd build +make -j8 + +# install +copy lidar_driver to board +path: /root/calibration_tools + +# execute +./lidar_driver 300000 + +# q&a +(base) root@localhost:~/calibration_tools# ./lidar_driver 300000 +cloud_points_count == [300000] +Livox SDK initializing. +Livox SDK has been initialized. +Livox SDK version 2.3.0 . +Started device discovery. +start_sampling error is -3 + +cd /root/app/detect-ui +./start.sh # start lidar +kill -9 pid diff --git a/lidar_driver/build.sh b/lidar_driver/build.sh new file mode 100644 index 0000000..b430c2a --- /dev/null +++ b/lidar_driver/build.sh @@ -0,0 +1,7 @@ +#!/usr/bin/env bash +rm -rf build +mkdir build +cd build +cmake .. +make +cp liblivox_sdk_wrapper.so ../ diff --git a/lidar_driver/cmake/cmakebase.cmake b/lidar_driver/cmake/cmakebase.cmake new file mode 100644 index 0000000..80256b6 --- /dev/null +++ b/lidar_driver/cmake/cmakebase.cmake @@ -0,0 +1,24 @@ +# this one is important +SET(CMAKE_SYSTEM_NAME Linux) +set(CMAKE_SYSTEM_PROCESSOR aarch64 ) + +SET(CMAKE_SYSTEM_VERSION 1) + +SET(SYSTEM_LINK_LIB + /usr/lib/aarch64-linux-gnu/libpthread.so + /usr/lib/aarch64-linux-gnu/librt.so + /usr/lib/aarch64-linux-gnu/libdl.so + /usr/lib/aarch64-linux-gnu/libm.so +) +SET(DO_FLAG -DO2) +SET(O_FLAG -O2) +SET(CMAKE_CXX_FLAGS + "${CMAKE_CXX_FLAGS} ${O_FLAG} -std=c++11 -Wno-deprecated-declarations -ffunction-sections -fdata-sections -Werror -Wno-psabi -Wno-pointer-arith -Wno-int-to-pointer-cast" +) +# SET(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -lstdc++) +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -lstdc++ -mcpu=cortex-a53 -fno-aggressive-loop-optimizations -ldl -ffunction-sections -fdata-sections -O2 -fstack-protector-strong -fPIC") +set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} -fPIE -pie -s -Wall -fsigned-char") + +set(CMAKE_CXX_STANDARD 11) +set(CMAKE_CXX_STANDARD_REQUIRED TRUE) + diff --git a/lidar_driver/cmake/project.cmake b/lidar_driver/cmake/project.cmake new file mode 100644 index 0000000..9686948 --- /dev/null +++ b/lidar_driver/cmake/project.cmake @@ -0,0 +1,96 @@ +# Project libs + +SET(SOC_LIBS +# libheif.a +# libheif.so + + # MPI_LIBS + libss_mpi.a + # ISP_SUPPORT + libss_ae.a + libss_isp.a + libot_isp.a + libss_awb.a + libss_dehaze.a + libss_extend_stats.a + libss_drc.a + libss_ldci.a + libss_crb.a + libss_bnr.a + libss_calcflicker.a + libss_ir_auto.a + libss_acs.a + libss_acs.a + libsns_os08a20.a + libsns_os05a10_2l_slave.a + libsns_imx347_slave.a + libsns_imx485.a + libsns_os04a10.a + libsns_os08b10.a + # ss_hnr + + # AUDIO_LIBA + libss_voice_engine.a + libss_upvqe.a + libss_dnvqe.a + libaac_comm.a + libaac_enc.a + libaac_dec.a + libaac_sbr_enc.a + libaac_sbr_dec.a + + # memset_s memcpy_s + libsecurec.a + + # HDMI lib + libss_hdmi.a + + # SVP + libss_ive.a + libss_md.a + libss_mau.a + libss_dpu_rect.a + libss_dpu_match.a + libss_dsp.a + libascend_protobuf.a + libsvp_acl.a + libprotobuf-c.a + + libacl_cblas.so + libacl_retr.so + libacl_tdt_queue.so + libadump.so + libaicpu_kernels.so + libaicpu_processer.so + libaicpu_prof.so + libaicpu_scheduler.so + libalog.so + libascendcl.so + libascend_protobuf.so + libcce_aicore.so + libcpu_kernels_context.so + libcpu_kernels.so + libc_sec.so + libdrv_aicpu.so + libdrvdevdrv.so + libdrv_dfx.so + liberror_manager.so + libge_common.so + libge_executor.so + libgraph.so + libmmpa.so + libmsprofiler.so + libmsprof.so + libopt_feature.so + libregister.so + libruntime.so + libslog.so + libtsdclient.so + +# libss_mcf.so +# libss_mcf_vi.so + libss_pqp.so +) + +add_definitions(-DSENSOR0_TYPE=SONY_IMX485_MIPI_8M_30FPS_12BIT) +# add_definitions(-DUSE_NCNN_SIMPLEOCV) \ No newline at end of file diff --git a/lidar_driver/cmake/ss928.cmake b/lidar_driver/cmake/ss928.cmake new file mode 100644 index 0000000..45a879f --- /dev/null +++ b/lidar_driver/cmake/ss928.cmake @@ -0,0 +1,5 @@ +SET(PLATFORM ss928) +SET(CMAKE_C_COMPILER /home/setups/aarch64-mix210-linux/aarch64-mix210-linux/bin/aarch64-mix210-linux-gcc) +SET(CMAKE_CXX_COMPILER /home/setups/aarch64-mix210-linux/aarch64-mix210-linux/bin/aarch64-mix210-linux-g++) +SET(CMAKE_STRIP /home/setups/aarch64-mix210-linux/aarch64-mix210-linux/bin/aarch64-mix210-linux-strip) +SET(CMAKE_ASM_COMPILER ${CMAKE_C_COMPILER}) diff --git a/lidar_driver/include/Livox/comm/comm_port.h b/lidar_driver/include/Livox/comm/comm_port.h new file mode 100644 index 0000000..4568ba6 --- /dev/null +++ b/lidar_driver/include/Livox/comm/comm_port.h @@ -0,0 +1,72 @@ +// +// The MIT License (MIT) +// +// Copyright (c) 2019 Livox. All rights reserved. +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +// SOFTWARE. +// + +#ifndef COMM_COMM_PORT_H_ +#define COMM_COMM_PORT_H_ + +#include +#include "protocol.h" + +namespace livox { +const uint32_t kCacheSize = 8192; +const uint32_t kMoveCacheLimit = 1536; + +typedef struct { + uint8_t buf[kCacheSize]; + uint32_t rd_idx; + uint32_t wr_idx; + uint32_t size; +} PortCache; + +class CommPort { + public: + CommPort(); + + ~CommPort(); + + int32_t Pack(uint8_t *o_buf, uint32_t o_buf_size, uint32_t *o_len, const CommPacket &i_packet); + + int32_t ParseCommStream(CommPacket *o_pack); + + uint8_t *FetchCacheFreeSpace(uint32_t *o_len); + + int32_t UpdateCacheWrIdx(uint32_t used_size); + + uint16_t GetAndUpdateSeqNum(); + + private: + uint32_t GetCacheTailSize(); + + uint32_t GetValidDataSize(); + + void UpdateCache(void); + + PortCache cache_; + Protocol *protocol_; + uint32_t parse_step_; + uint16_t seq_num_; +}; + +} // namespace livox +#endif // COMM_COMM_PORT_H_ diff --git a/lidar_driver/include/Livox/comm/protocol.h b/lidar_driver/include/Livox/comm/protocol.h new file mode 100644 index 0000000..f598308 --- /dev/null +++ b/lidar_driver/include/Livox/comm/protocol.h @@ -0,0 +1,82 @@ +// +// The MIT License (MIT) +// +// Copyright (c) 2019 Livox. All rights reserved. +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +// SOFTWARE. +// + +#ifndef COMM_PROTOCOL_H_ +#define COMM_PROTOCOL_H_ + +#include + +namespace livox { +typedef struct CommPacket CommPacket; + +typedef int (*RequestPackCb)(CommPacket *packet); + +typedef enum { kRequestPack, kAckPack, kMsgPack } PacketType; + +typedef enum { kLidarSdk, kRsvd1, kProtocolUndef } ProtocolType; + +typedef enum { kNoNeed, kNeedAck, kDelayAck } NeedAckType; + +typedef enum { kParseSuccess, kParseFail } ParseResult; + +typedef struct CommPacket { + uint8_t packet_type; + uint8_t protocol; + uint8_t protocol_version; + uint8_t cmd_set; + uint32_t cmd_code; + uint32_t sender; + uint32_t sub_sender; + uint32_t receiver; + uint32_t sub_receiver; + uint32_t seq_num; + uint8_t *data; + uint16_t data_len; + uint32_t padding; + // RequestPackCb *ack_request_cb; + // uint32_t retry_times; + // uint32_t timeout; +} CommPacket; + +class Protocol { + public: + virtual ~Protocol(){}; + + virtual int32_t ParsePacket(uint8_t *i_buf, uint32_t i_len, CommPacket *o_packet) = 0; + + virtual int32_t Pack(uint8_t *o_buf, uint32_t o_buf_size, uint32_t *o_len, const CommPacket &i_packet) = 0; + + virtual uint32_t GetPreambleLen() = 0; + + virtual uint32_t GetPacketWrapperLen() = 0; + + virtual uint32_t GetPacketLen(uint8_t *buf) = 0; + + virtual int32_t CheckPreamble(uint8_t *buf) = 0; + + virtual int32_t CheckPacket(uint8_t *buf) = 0; +}; + +} // namespace livox +#endif // COMM_PROTOCOL_H_ diff --git a/lidar_driver/include/Livox/config.h b/lidar_driver/include/Livox/config.h new file mode 100644 index 0000000..9852267 --- /dev/null +++ b/lidar_driver/include/Livox/config.h @@ -0,0 +1,49 @@ +// +// The MIT License (MIT) +// +// Copyright (c) 2019 Livox. All rights reserved. +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +// SOFTWARE. +// + +#ifndef CONFIG_H_ +#define CONFIG_H_ + +#if defined(__linux__) + #include + #include + #include + #define HAVE_EPOLL 1 +#elif defined(_WIN32) + #include + #define HAVE_SELECT 1 +#elif defined(__APPLE__) || defined(__FreeBSD__) || defined(__OpenBSD__) || defined (__NetBSD__) + #include + #include + #include + #include + #define HAVE_KQUEUE 1 +#else + #include + #define HAVE_POLL 1 +#endif + +#endif // CONFIG_H_ + + diff --git a/lidar_driver/include/Livox/livox_def.h b/lidar_driver/include/Livox/livox_def.h new file mode 100644 index 0000000..d627db3 --- /dev/null +++ b/lidar_driver/include/Livox/livox_def.h @@ -0,0 +1,855 @@ +// +// The MIT License (MIT) +// +// Copyright (c) 2019 Livox. All rights reserved. +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +// SOFTWARE. +// + +#ifndef LIVOX_DEF_H_ +#define LIVOX_DEF_H_ + +#include + +#define kMaxLidarCount 32 + +/** Device type. */ +typedef enum { + kDeviceTypeHub = 0, /**< Livox Hub. */ + kDeviceTypeLidarMid40 = 1, /**< Mid-40. */ + kDeviceTypeLidarTele = 2, /**< Tele. */ + kDeviceTypeLidarHorizon = 3, /**< Horizon. */ + kDeviceTypeLidarMid70 = 6, /**< Livox Mid-70. */ + kDeviceTypeLidarAvia = 7 /**< Avia. */ +} DeviceType; + +/** Lidar state. */ +typedef enum { + kLidarStateInit = 0, /**< Initialization state. */ + kLidarStateNormal = 1, /**< Normal work state. */ + kLidarStatePowerSaving = 2, /**< Power-saving state. */ + kLidarStateStandBy = 3, /**< Standby state. */ + kLidarStateError = 4, /**< Error state. */ + kLidarStateUnknown = 5 /**< Unknown state. */ +} LidarState; + +/** Lidar mode. */ +typedef enum { + kLidarModeNormal = 1, /**< Normal mode. */ + kLidarModePowerSaving = 2, /**< Power-saving mode. */ + kLidarModeStandby = 3 /**< Standby mode. */ +} LidarMode; + +/** Lidar feature. */ +typedef enum { + kLidarFeatureNone = 0, /**< No feature. */ + kLidarFeatureRainFog = 1 /**< Rain and fog feature. */ +} LidarFeature; + +/** Lidar IP mode. */ +typedef enum { + kLidarDynamicIpMode = 0, /**< Dynamic IP. */ + kLidarStaticIpMode = 1 /**< Static IP. */ +} LidarIpMode; + +/** Lidar Scan Pattern. */ +typedef enum { + kNoneRepetitiveScanPattern = 0, /**< None Repetitive Scan Pattern. */ + kRepetitiveScanPattern = 1, /**< Repetitive Scan Pattern. */ +} LidarScanPattern; + +/** Function return value definition. */ +typedef enum { + kStatusSendFailed = -9, /**< Command send failed. */ + kStatusHandlerImplNotExist = -8, /**< Handler implementation not exist. */ + kStatusInvalidHandle = -7, /**< Device handle invalid. */ + kStatusChannelNotExist = -6, /**< Command channel not exist. */ + kStatusNotEnoughMemory = -5, /**< No enough memory. */ + kStatusTimeout = -4, /**< Operation timeouts. */ + kStatusNotSupported = -3, /**< Operation is not supported on this device. */ + kStatusNotConnected = -2, /**< Requested device is not connected. */ + kStatusFailure = -1, /**< Failure. */ + kStatusSuccess = 0 /**< Success. */ +} LivoxStatus; + +/** Fuction return value defination, refer to \ref LivoxStatus. */ +typedef int32_t livox_status; + +/** Device update type, indicating the change of device connection or working state. */ +typedef enum { + kEventConnect = 0, /**< Device is connected. */ + kEventDisconnect = 1, /**< Device is removed. */ + kEventStateChange = 2, /**< Device working state changes or an error occurs. */ + kEventHubConnectionChange = 3 /**< Hub is connected or LiDAR unit(s) is/are removed. */ +} DeviceEvent; + +/** Timestamp sync mode define. */ +typedef enum { + kTimestampTypeNoSync = 0, /**< No sync signal mode. */ + kTimestampTypePtp = 1, /**< 1588v2.0 PTP sync mode. */ + kTimestampTypeRsvd = 2, /**< Reserved use. */ + kTimestampTypePpsGps = 3, /**< pps+gps sync mode. */ + kTimestampTypePps = 4, /**< pps only sync mode. */ + kTimestampTypeUnknown = 5 /**< Unknown mode. */ +} TimestampType; + +/** Point data type. */ +typedef enum { + kCartesian, /**< Cartesian coordinate point cloud. */ + kSpherical, /**< Spherical coordinate point cloud. */ + kExtendCartesian, /**< Extend cartesian coordinate point cloud. */ + kExtendSpherical, /**< Extend spherical coordinate point cloud. */ + kDualExtendCartesian, /**< Dual extend cartesian coordinate point cloud. */ + kDualExtendSpherical, /**< Dual extend spherical coordinate point cloud. */ + kImu, /**< IMU data. */ + kTripleExtendCartesian, /**< Triple extend cartesian coordinate point cloud. */ + kTripleExtendSpherical, /**< Triple extend spherical coordinate point cloud. */ + kMaxPointDataType /**< Max Point Data Type. */ +} PointDataType; + +/** Point cloud return mode. */ +typedef enum { + kFirstReturn, /**< First single return mode . */ + kStrongestReturn, /**< Strongest single return mode. */ + kDualReturn, /**< Dual return mode. */ + kTripleReturn, /**< Triple return mode. */ +} PointCloudReturnMode; + +/** IMU push frequency. */ +typedef enum { + kImuFreq0Hz, /**< IMU push closed. */ + kImuFreq200Hz, /**< IMU push frequency 200Hz. */ +} ImuFreq; + +#pragma pack(1) + +#define LIVOX_SDK_MAJOR_VERSION 2 +#define LIVOX_SDK_MINOR_VERSION 3 +#define LIVOX_SDK_PATCH_VERSION 0 + +#define kBroadcastCodeSize 16 + +/** The numeric version information struct. */ +typedef struct { + int major; /**< major number */ + int minor; /**< minor number */ + int patch; /**< patch number */ +} LivoxSdkVersion; + +/** Cartesian coordinate format. */ +typedef struct { + int32_t x; /**< X axis, Unit:mm */ + int32_t y; /**< Y axis, Unit:mm */ + int32_t z; /**< Z axis, Unit:mm */ + uint8_t reflectivity; /**< Reflectivity */ +} LivoxRawPoint; + +/** Spherical coordinate format. */ +typedef struct { + uint32_t depth; /**< Depth, Unit: mm */ + uint16_t theta; /**< Zenith angle[0, 18000], Unit: 0.01 degree */ + uint16_t phi; /**< Azimuth[0, 36000], Unit: 0.01 degree */ + uint8_t reflectivity; /**< Reflectivity */ +} LivoxSpherPoint; + +/** Standard point cloud format */ +typedef struct { + float x; /**< X axis, Unit:m */ + float y; /**< Y axis, Unit:m */ + float z; /**< Z axis, Unit:m */ + uint8_t reflectivity; /**< Reflectivity */ +} LivoxPoint; + +/** Extend cartesian coordinate format. */ +typedef struct { + int32_t x; /**< X axis, Unit:mm */ + int32_t y; /**< Y axis, Unit:mm */ + int32_t z; /**< Z axis, Unit:mm */ + uint8_t reflectivity; /**< Reflectivity */ + uint8_t tag; /**< Tag */ +} LivoxExtendRawPoint; + +/** Extend spherical coordinate format. */ +typedef struct { + uint32_t depth; /**< Depth, Unit: mm */ + uint16_t theta; /**< Zenith angle[0, 18000], Unit: 0.01 degree */ + uint16_t phi; /**< Azimuth[0, 36000], Unit: 0.01 degree */ + uint8_t reflectivity; /**< Reflectivity */ + uint8_t tag; /**< Tag */ +} LivoxExtendSpherPoint; + +/** Dual extend cartesian coordinate format. */ +typedef struct { + int32_t x1; /**< X axis, Unit:mm */ + int32_t y1; /**< Y axis, Unit:mm */ + int32_t z1; /**< Z axis, Unit:mm */ + uint8_t reflectivity1; /**< Reflectivity */ + uint8_t tag1; /**< Tag */ + int32_t x2; /**< X axis, Unit:mm */ + int32_t y2; /**< Y axis, Unit:mm */ + int32_t z2; /**< Z axis, Unit:mm */ + uint8_t reflectivity2; /**< Reflectivity */ + uint8_t tag2; /**< Tag */ +} LivoxDualExtendRawPoint; + +/** Dual extend spherical coordinate format. */ +typedef struct { + uint16_t theta; /**< Zenith angle[0, 18000], Unit: 0.01 degree */ + uint16_t phi; /**< Azimuth[0, 36000], Unit: 0.01 degree */ + uint32_t depth1; /**< Depth, Unit: mm */ + uint8_t reflectivity1; /**< Reflectivity */ + uint8_t tag1; /**< Tag */ + uint32_t depth2; /**< Depth, Unit: mm */ + uint8_t reflectivity2; /**< Reflectivity */ + uint8_t tag2; /**< Tag */ +} LivoxDualExtendSpherPoint; + +/** Triple extend cartesian coordinate format. */ +typedef struct { + int32_t x1; /**< X axis, Unit:mm */ + int32_t y1; /**< Y axis, Unit:mm */ + int32_t z1; /**< Z axis, Unit:mm */ + uint8_t reflectivity1; /**< Reflectivity */ + uint8_t tag1; /**< Tag */ + int32_t x2; /**< X axis, Unit:mm */ + int32_t y2; /**< Y axis, Unit:mm */ + int32_t z2; /**< Z axis, Unit:mm */ + uint8_t reflectivity2; /**< Reflectivity */ + uint8_t tag2; /**< Tag */ + int32_t x3; /**< X axis, Unit:mm */ + int32_t y3; /**< Y axis, Unit:mm */ + int32_t z3; /**< Z axis, Unit:mm */ + uint8_t reflectivity3; /**< Reflectivity */ + uint8_t tag3; /**< Tag */ +} LivoxTripleExtendRawPoint; + +/** Triple extend spherical coordinate format. */ +typedef struct { + uint16_t theta; /**< Zenith angle[0, 18000], Unit: 0.01 degree */ + uint16_t phi; /**< Azimuth[0, 36000], Unit: 0.01 degree */ + uint32_t depth1; /**< Depth, Unit: mm */ + uint8_t reflectivity1; /**< Reflectivity */ + uint8_t tag1; /**< Tag */ + uint32_t depth2; /**< Depth, Unit: mm */ + uint8_t reflectivity2; /**< Reflectivity */ + uint8_t tag2; /**< Tag */ + uint32_t depth3; /**< Depth, Unit: mm */ + uint8_t reflectivity3; /**< Reflectivity */ + uint8_t tag3; /**< Tag */ +} LivoxTripleExtendSpherPoint; + +/** IMU data format. */ +typedef struct { + float gyro_x; /**< Gyroscope X axis, Unit:rad/s */ + float gyro_y; /**< Gyroscope Y axis, Unit:rad/s */ + float gyro_z; /**< Gyroscope Z axis, Unit:rad/s */ + float acc_x; /**< Accelerometer X axis, Unit:g */ + float acc_y; /**< Accelerometer Y axis, Unit:g */ + float acc_z; /**< Accelerometer Z axis, Unit:g */ +} LivoxImuPoint; + +/** LiDAR error code. */ +typedef struct { + uint32_t temp_status : 2; /**< 0: Temperature in Normal State. 1: High or Low. 2: Extremely High or Extremely Low. */ + uint32_t volt_status : 2; /**< 0: Voltage in Normal State. 1: High. 2: Extremely High. */ + uint32_t motor_status : 2; /**< 0: Motor in Normal State. 1: Motor in Warning State. 2:Motor in Error State, Unable to Work. */ + uint32_t dirty_warn : 2; /**< 0: Not Dirty or Blocked. 1: Dirty or Blocked. */ + uint32_t firmware_err : 1; /**< 0: Firmware is OK. 1: Firmware is Abnormal, Need to be Upgraded. */ + uint32_t pps_status : 1; /**< 0: No PPS Signal. 1: PPS Signal is OK. */ + uint32_t device_status : 1; /**< 0: Normal. 1: Warning for Approaching the End of Service Life. */ + uint32_t fan_status : 1; /**< 0: Fan in Normal State. 1: Fan in Warning State. */ + uint32_t self_heating : 1; /**< 0: Normal. 1: Low Temperature Self Heating On. */ + uint32_t ptp_status : 1; /**< 0: No 1588 Signal. 1: 1588 Signal is OK. */ + /** 0: System dose not start time synchronization. + * 1: Using PTP 1588 synchronization. + * 2: Using GPS synchronization. + * 3: Using PPS synchronization. + * 4: System time synchronization is abnormal.(The highest priority synchronization signal is abnormal) + */ + uint32_t time_sync_status : 3; + uint32_t rsvd : 13; /**< Reserved. */ + uint32_t system_status : 2; /**< 0: Normal. 1: Warning. 2: Error. */ +} LidarErrorCode; + +/** Hub error code. */ +typedef struct { + /** 0: No synchronization signal. + * 1: 1588 synchronization. + * 2: GPS synchronization. + * 3: System time synchronization is abnormal.(The highest priority synchronization signal is abnormal) + */ + uint32_t sync_status : 2; + uint32_t temp_status : 2; /**< 0: Temperature in Normal State. 1: High or Low. 2: Extremely High or Extremely Low. */ + uint32_t lidar_status : 1; /**< 0: LiDAR State is Normal. 1: LiDAR State is Abnormal. */ + uint32_t lidar_link_status : 1; /**< 0: LiDAR Connection is Normal. 1: LiDAR Connection is Abnormal. */ + uint32_t firmware_err : 1; /**< 0: LiDAR Firmware is OK. 1: LiDAR Firmware is Abnormal, Need to be Upgraded. */ + uint32_t rsvd : 23; /**< Reserved. */ + uint32_t system_status : 2; /**< 0: Normal. 1: Warning. 2: Error. */ +} HubErrorCode; + +/** + * Device error message. + */ +typedef union { + uint32_t error_code; /**< Error code. */ + LidarErrorCode lidar_error_code; /**< Lidar error code. */ + HubErrorCode hub_error_code; /**< Hub error code. */ +} ErrorMessage; + +/** Point cloud packet. */ +typedef struct { + uint8_t version; /**< Packet protocol version. */ + uint8_t slot; /**< Slot number used for connecting LiDAR. */ + uint8_t id; /**< LiDAR id. */ + uint8_t rsvd; /**< Reserved. */ + uint32_t err_code; /**< Device error status indicator information. */ + uint8_t timestamp_type; /**< Timestamp type. */ + /** Point cloud coordinate format, refer to \ref PointDataType . */ + uint8_t data_type; + uint8_t timestamp[8]; /**< Nanosecond or UTC format timestamp. */ + uint8_t data[1]; /**< Point cloud data. */ +} LivoxEthPacket; + +/** Information of LiDAR work state. */ +typedef union { + uint32_t progress; /**< LiDAR work state switching progress. */ + ErrorMessage status_code; /**< LiDAR work state status code. */ +} StatusUnion; + +/** Information of the connected LiDAR or hub. */ +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code, null-terminated string, 15 characters at most. */ + uint8_t handle; /**< Device handle. */ + uint8_t slot; /**< Slot number used for connecting LiDAR. */ + uint8_t id; /**< LiDAR id. */ + uint8_t type; /**< Device type, refer to \ref DeviceType. */ + uint16_t data_port; /**< Point cloud data UDP port. */ + uint16_t cmd_port; /**< Control command UDP port. */ + uint16_t sensor_port; /**< IMU data UDP port. */ + char ip[16]; /**< IP address. */ + LidarState state; /**< LiDAR state. */ + LidarFeature feature; /**< LiDAR feature. */ + StatusUnion status; /**< LiDAR work state status. */ + uint8_t firmware_version[4]; /**< Firmware version. */ +} DeviceInfo; + +/** The information of broadcast device. */ +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code, null-terminated string, 15 characters at most. */ + uint8_t dev_type; /**< Device type, refer to \ref DeviceType. */ + uint16_t reserved; /**< Reserved. */ + char ip[16]; /**< Device ip. */ +} BroadcastDeviceInfo; + +/** The information of LiDAR units that are connected to the Livox Hub. */ +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code, null-terminated string, 15 characters at most. */ + uint8_t dev_type; /**< Device type, refer to \ref DeviceType. */ + uint8_t version[4]; /**< Firmware version. */ + uint8_t slot; /**< Slot number used for connecting LiDAR units. */ + uint8_t id; /**< Device id. */ +} ConnectedLidarInfo; + +/** LiDAR mode configuration information. */ +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code, null-terminated string, 15 characters at most. */ + uint8_t state; /**< LiDAR state, refer to \ref LidarMode. */ +} LidarModeRequestItem; + +typedef struct { + uint8_t ret_code; /**< Return code. */ + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ +} ReturnCode; + +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ +} DeviceBroadcastCode; + +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ + uint8_t feature; /**< Close or open the rain and fog feature. */ +} RainFogSuppressRequestItem; + +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ + uint8_t state; /**< Fan state: 1 for turn on fan, 0 for turn off fan. */ +} FanControlRequestItem; + +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ +} GetFanStateRequestItem; + +typedef struct { + uint8_t ret_code; /**< Return code. */ + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ + uint8_t state; /**< Fan state: 1 for fan is on, 0 for fan is off. */ +} GetFanStateResponseItem; + +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ + uint8_t mode; /**< Point cloud return mode, refer to \ref PointCloudReturnMode. */ +} SetPointCloudReturnModeRequestItem; + +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ +} GetPointCloudReturnModeRequestItem; + +typedef struct { + uint8_t ret_code; /**< Return code. */ + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ + uint8_t mode; /**< Point cloud return mode, refer to \ref PointCloudReturnMode. */ +} GetPointCloudReturnModeResponseItem; + +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ + uint8_t freq; /**< IMU push frequency, refer to \ref ImuFreq. */ +} SetImuPushFrequencyRequestItem; + + +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ +} GetImuPushFrequencyRequestItem; + +typedef struct { + uint8_t ret_code; /**< Return code. */ + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ + uint8_t freq; /**< IMU push frequency, refer to \ref ImuFreq. */ +} GetImuPushFrequencyResponseItem; + +/** LiDAR configuration information. */ +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Device broadcast code. */ + float roll; /**< Roll angle, unit: degree. */ + float pitch; /**< Pitch angle, unit: degree. */ + float yaw; /**< Yaw angle, unit: degree. */ + int32_t x; /**< X translation, unit: mm. */ + int32_t y; /**< Y translation, unit: mm. */ + int32_t z; /**< Z translation, unit: mm. */ +} ExtrinsicParameterRequestItem; + +/** LiDAR extrinsic parameters. */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + char broadcast_code[kBroadcastCodeSize]; /**< Broadcast code. */ + float roll; /**< Roll angle, unit: degree. */ + float pitch; /**< Pitch angle, unit: degree. */ + float yaw; /**< Yaw angle, unit: degree. */ + int32_t x; /**< X translation, unit: mm. */ + int32_t y; /**< Y translation, unit: mm. */ + int32_t z; /**< Z translation, unit: mm. */ +} ExtrinsicParameterResponseItem; + +typedef struct { + char broadcast_code[kBroadcastCodeSize]; /**< Broadcast code. */ + uint8_t state; /**< LiDAR state. */ + uint8_t feature; /**< LiDAR feature. */ + StatusUnion error_union; /**< LiDAR work state. */ +} LidarStateItem; + +/** + * The request body for the command of handshake. + */ +typedef struct { + uint32_t ip_addr; /**< IP address of the device. */ + uint16_t data_port; /**< UDP port of the data connection. */ + uint16_t cmd_port; /**< UDP port of the command connection. */ + uint16_t sensor_port; /**< UDP port of the sensor connection. */ +} HandshakeRequest; + +/** + * The response body of querying device information. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t firmware_version[4]; /**< Firmware version. */ +} DeviceInformationResponse; + +/** + * The request body of the command for setting device's IP mode. + */ +typedef struct { + uint8_t ip_mode; /**< IP address mode: 0 for dynamic IP address, 1 for static IP address. */ + uint32_t ip_addr; /**< IP address. */ +} SetDeviceIPModeRequest; + +/** + * The response body of getting device's IP mode. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t ip_mode; /**< IP address mode: 0 for dynamic IP address, 1 for static IP address. */ + uint32_t ip_addr; /**< IP address. */ + uint32_t net_mask; /**< Subnet mask. */ + uint32_t gw_addr; /**< Gateway address. */ +} GetDeviceIpModeResponse; + +/** + * The request body of the command for setting static device's IP mode. + */ +typedef struct { + uint32_t ip_addr; /**< IP address. */ + uint32_t net_mask; /**< Subnet mask. */ + uint32_t gw_addr; /**< Gateway address. */ +} SetStaticDeviceIpModeRequest; + +/** + * The body of heartbeat response. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t state; /**< Working state. */ + uint8_t feature; /**< LiDAR feature. */ + StatusUnion error_union; /**< LiDAR work state. */ +} HeartbeatResponse; + +/** + * The error code of Getting/Setting Device's Parameters. + */ +typedef enum { + kKeyNoError = 0, /**< No Error. */ + kKeyNotSupported = 1, /**< The key is not supported. */ + kKeyExecFailed = 2, /**< Execution failed. */ + kKeyNotSupportedWritingState = 3, /**< The key cannot be written. */ + kKeyValueError = 4, /**< Wrong value. */ + kKeyValueLengthError = 5, /**< Wrong value length. */ + kKeyNoEnoughMemory = 6, /**< Reading parameter length limit. */ + kKeyLengthError = 7, /**< The number of parameters does not match. */ +} KeyErrorCode; + +/** + * The response body of setting device's parameter. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint16_t error_param_key; /**< Error Key. */ + uint8_t error_code; /**< Error code, refer to \ref KeyErrorCode. */ +} DeviceParameterResponse; + +/** + * Keys of device's parameters. + */ +typedef enum { + kKeyDefault = 0, /**< Default key name. */ + kKeyHighSensetivity = 1, /**< Key to get/set LiDAR' Sensetivity. */ + kKeyScanPattern = 2, /**< Key to get/set LiDAR' ScanPattern. */ + kKeySlotNum = 3, /**< Key to get/set LiDAR' Slot number. */ +} DeviceParamKeyName; + +/** + * Key and value of device's parameters. + */ +typedef struct { + uint16_t key; /*< Key, refer to \ref DeviceParamKeyName. */ + uint16_t length; /*< Length of value */ + uint8_t value[1]; /*< Value */ +} KeyValueParam; + +/** + * The response body of getting device's parameter. + */ +typedef struct { + DeviceParameterResponse rsp; /*< Return code. */ + KeyValueParam kv; /*< Key and value of device's parameters. */ +} GetDeviceParameterResponse; + +/** + * The request body for the command of getting device's parameters. + */ +typedef struct { + uint8_t param_num; /*< Number of key. */ + uint16_t key[1]; /*< Key, refer to \ref DeviceParamKeyName. */ +} GetDeviceParameterRequest; + +/** + * The request body for the command of resetting device's parameters. + */ +typedef struct { + uint8_t flag; /*< 0: for resetting all keys, 1: for resetting part of keys. */ + uint8_t key_num; /*< number of keys to reset. */ + uint16_t key[1]; /*< Keys to reset, refer to \ref DeviceParamKeyName. */ +} ResetDeviceParameterRequest; + +/** + * The request body for the command of setting Livox LiDAR's parameters. + */ +typedef struct { + float roll; /**< Roll angle, unit: degree. */ + float pitch; /**< Pitch angle, unit: degree. */ + float yaw; /**< Yaw angle, unit: degree. */ + int32_t x; /**< X translation, unit: mm. */ + int32_t y; /**< Y translation, unit: mm. */ + int32_t z; /**< Z translation, unit: mm. */ +} LidarSetExtrinsicParameterRequest; + +/** + * The response body of getting Livox LiDAR's parameters. + */ +typedef struct { + uint8_t ret_code; + float roll; /**< Roll angle, unit: degree. */ + float pitch; /**< Pitch angle, unit: degree. */ + float yaw; /**< Yaw angle, unit: degree. */ + int32_t x; /**< X translation, unit: mm. */ + int32_t y; /**< Y translation, unit: mm. */ + int32_t z; /**< Z translation, unit: mm. */ +} LidarGetExtrinsicParameterResponse; + +/** + * The response body of getting the Livox LiDAR's fan state. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t state; /**< Fan state: 1 for fan is on, 0 for fan is off. */ +} LidarGetFanStateResponse; + +/** + * The response body of getting the Livox LiDAR's point cloud return mode. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t mode; /**< Point cloud return mode, refer to \ref PointCloudReturnMode. */ +} LidarGetPointCloudReturnModeResponse; + + +/** + * The response body of getting the Livox LiDAR's IMU push frequency. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t freq; /**< IMU push frequency, refer to \ref ImuFreq. */ +} LidarGetImuPushFrequencyResponse; + +/** + * The response body of setting the Livox LiDAR's Sync time. + */ +typedef struct { + uint8_t year; + uint8_t month; + uint8_t day; + uint8_t hour; + uint32_t microsecond; +} LidarSetUtcSyncTimeRequest; + +/** + * The response body of querying the information of LiDAR units connected to the Livox Hub. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of device_info_list. */ + ConnectedLidarInfo device_info_list[1]; /**< Connected lidars information list. */ +} HubQueryLidarInformationResponse; + +/** + * The request body of setting Livox Hub's working mode. + */ +typedef struct { + uint8_t count; /**< Count of config_list. */ + LidarModeRequestItem config_list[1]; /**< LiDAR mode configuration list. */ +} HubSetModeRequest; + +/** + * The response of setting Livox Hub's working mode. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of ret_state_list. */ + ReturnCode ret_state_list[1]; /**< Return status list. */ +} HubSetModeResponse; + +/** + * The request body of toggling the power supply of the slot. + */ +typedef struct { + uint8_t slot; /**< Slot of the hub. */ + uint8_t state; /**< Status of toggling the power supply. */ +} HubControlSlotPowerRequest; + +/** + * The request body of setting the Livox Hub's parameters. + */ +typedef struct { + uint8_t count; /**< Count of cfg_param_list. */ + ExtrinsicParameterRequestItem parameter_list[1]; /**< Extrinsic parameter configuration list. */ +} HubSetExtrinsicParameterRequest; + +/** + * The response body of setting the Livox Hub's parameters. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of ret_code_list. */ + ReturnCode ret_code_list[1]; /**< Return code list. */ +} HubSetExtrinsicParameterResponse; + +/** + * The request body of getting the Livox Hub's parameters. + */ +typedef struct { + uint8_t count; /**< Count of code_list. */ + DeviceBroadcastCode code_list[1]; /**< Broadcast code list. */ +} HubGetExtrinsicParameterRequest; + +/** + * The response body of getting the Livox Hub's parameters. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of code_list. */ + ExtrinsicParameterResponseItem parameter_list[1]; /**< Extrinsic parameter list. */ +} HubGetExtrinsicParameterResponse; + +/** + * The response body of getting sub LiDAR's state conneted to Hub. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of state_list. */ + LidarStateItem state_list[1]; /**< LiDAR units state list. */ +} HubQueryLidarStatusResponse; + +/** + * The request body of toggling the Livox Hub's rain and fog mode. + */ +typedef struct { + uint8_t count; /**< Count of lidar_cfg_list. */ + RainFogSuppressRequestItem lidar_cfg_list[1]; /**< Rain fog suppress configuration list. */ +} HubRainFogSuppressRequest; + +/** + * The response body of toggling the Livox Hub's rain and fog mode. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of ret_state_list. */ + ReturnCode ret_state_list[1]; /**< Return state list */ +} HubRainFogSuppressResponse; + +/** +* The response body of getting Hub slots' power state. +*/ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint16_t slot_power_state; /**< Slot power status. */ +} HubQuerySlotPowerStatusResponse; + +/** + * The request body of controlling the sub LiDAR's fan state conneted to Hub. + */ +typedef struct { + uint8_t count; /**< Count of lidar_cfg_list. */ + FanControlRequestItem lidar_cfg_list[1]; /**< Fan control configuration list. */ +} HubFanControlRequest; + +/** + * The response body of controlling the sub LiDAR's fan state conneted to Hub. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of return_list. */ + ReturnCode return_list[1]; /**< Return list */ +} HubFanControlResponse; + +/** + * The request body of getting the sub LiDAR's fan state conneted to Hub. + */ +typedef struct { + uint8_t count; /**< Count of lidar_cfg_list. */ + GetFanStateRequestItem lidar_cfg_list[1]; /**< Get Fan state list. */ +} HubGetFanStateRequest; + +/** + * The response body of getting the sub LiDAR's fan state conneted to Hub. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of return_list. */ + GetFanStateResponseItem return_list[1]; /**< Fan state list. */ +} HubGetFanStateResponse; + +/** + * The request body of setting point cloud return mode of sub LiDAR conneted to Hub. + */ +typedef struct { + uint8_t count; /**< Count of lidar_cfg_list. */ + SetPointCloudReturnModeRequestItem lidar_cfg_list[1]; /**< Point cloud return mode configuration list. */ +} HubSetPointCloudReturnModeRequest; + +/** + * The response body of setting point cloud return mode of sub LiDAR conneted to Hub. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of return_list. */ + ReturnCode return_list[1]; /**< Return list. */ +} HubSetPointCloudReturnModeResponse; + +/** + * The request body of getting sub LiDAR's point cloud return mode conneted to Hub. + */ +typedef struct { + uint8_t count; /**< Count of lidar_cfg_list. */ + GetPointCloudReturnModeRequestItem lidar_cfg_list[1]; /**< Get point cloud return mode list. */ +} HubGetPointCloudReturnModeRequest; + +/** + * The response body of getting sub LiDAR's point cloud return mode conneted to Hub. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of return_list. */ + GetPointCloudReturnModeResponseItem return_list[1]; /**< Point cloud return mode list. */ +} HubGetPointCloudReturnModeResponse; + +/** + * The request body of setting IMU push frequency of sub LiDAR conneted to Hub. + */ +typedef struct { + uint8_t count; /**< Count of lidar_cfg_list. */ + SetImuPushFrequencyRequestItem lidar_cfg_list[1]; /**< IMU push frequency configuration list. */ +} HubSetImuPushFrequencyRequest; + +/** + * The response body of setting IMU push frequency of sub LiDAR conneted to Hub. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of return_list. */ + ReturnCode return_list[1]; /**< Return list. */ +} HubSetImuPushFrequencyResponse; + +/** + * The request body of getting sub LiDAR's IMU push frequency conneted to Hub. + */ +typedef struct { + uint8_t count; /**< Count of lidar_cfg_list. */ + GetImuPushFrequencyRequestItem lidar_cfg_list[1]; /**< Get IMU push frequency list. */ +} HubGetImuPushFrequencyRequest; + +/** + * The response body of getting sub LiDAR's IMU push frequency conneted to Hub. + */ +typedef struct { + uint8_t ret_code; /**< Return code. */ + uint8_t count; /**< Count of return_list. */ + GetImuPushFrequencyResponseItem return_list[1]; /**< IMU push frequency list. */ +} HubGetImuPushFrequencyResponse; + +#pragma pack() + +#endif // LIVOX_DEF_H_ diff --git a/lidar_driver/include/Livox/livox_sdk.h b/lidar_driver/include/Livox/livox_sdk.h new file mode 100644 index 0000000..498da7b --- /dev/null +++ b/lidar_driver/include/Livox/livox_sdk.h @@ -0,0 +1,999 @@ +// +// The MIT License (MIT) +// +// Copyright (c) 2019 Livox. All rights reserved. +// +// Permission is hereby granted, free of charge, to any person obtaining a copy +// of this software and associated documentation files (the "Software"), to deal +// in the Software without restriction, including without limitation the rights +// to use, copy, modify, merge, publish, distribute, sublicense, and/or sell +// copies of the Software, and to permit persons to whom the Software is +// furnished to do so, subject to the following conditions: +// +// The above copyright notice and this permission notice shall be included in +// all copies or substantial portions of the Software. +// +// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR +// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, +// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE +// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER +// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, +// OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE +// SOFTWARE. +// + +#ifndef LIVOX_SDK_H_ +#define LIVOX_SDK_H_ + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include +#include "livox_def.h" + +/** +* Return SDK's version information in a numeric form. +* @param version Pointer to a version structure for returning the version information. +*/ +void GetLivoxSdkVersion(LivoxSdkVersion *version); + +/** + * Disable console log output. + */ +void DisableConsoleLogger(); + +/** + * Initialize the SDK. + * @return true if successfully initialized, otherwise false. + */ +bool Init(); + +/** + * Start the device scanning routine which runs on a separate thread. + * @return true if successfully started, otherwise false. + */ +bool Start(); + +/** + * Uninitialize the SDK. + */ +void Uninit(); + +/** +* Save the log file. +*/ +void SaveLoggerFile(); + +/** + * @c SetBroadcastCallback response callback function. + * @param info information of the broadcast device, becomes invalid after the function returns. + */ +typedef void (*DeviceBroadcastCallback)(const BroadcastDeviceInfo *info); + +/** + * Set the callback of listening device broadcast message. When broadcast message is received from Livox Hub/LiDAR, cb + * is called. + * @param cb callback for device broadcast. + */ +void SetBroadcastCallback(DeviceBroadcastCallback cb); + +/** + * @c SetDeviceStateUpdateCallback response callback function. + * @param device information of the connected device. + * @param type the update type that indicates connection/disconnection of the device or change of working state. + */ +typedef void (*DeviceStateUpdateCallback)(const DeviceInfo *device, DeviceEvent type); + +/** + * @brief Add a callback for device connection or working state changing event. + * @note Livox SDK supports two hardware connection modes. 1: Directly connecting to the LiDAR device; 2. Connecting to + * the LiDAR device(s) via the Livox Hub. In the first mode, connection/disconnection of every LiDAR unit is reported by + * this callback. In the second mode, only connection/disconnection of the Livox Hub is reported by this callback. If + * you want to get information of the LiDAR unit(s) connected to hub, see \ref HubQueryLidarInformation. + * @note 3 conditions can trigger this callback: + * 1. Connection and disconnection of device. + * 2. A change of device working state. + * 3. An error occurs. + * @param cb callback for device connection/disconnection. + */ +void SetDeviceStateUpdateCallback(DeviceStateUpdateCallback cb); + +/** + * Add a broadcast code to the connecting list and only devices with broadcast code in this list will be connected. The + * broadcast code is unique for every device. + * @param broadcast_code device's broadcast code. + * @param handle device handle. For Livox Hub, the handle is always 31; for LiDAR units connected to the Livox Hub, + * the corresponding handle is (slot-1)*3+id-1. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status AddHubToConnect(const char *broadcast_code, uint8_t *handle); + +/** + * Add a broadcast code to the connecting list and only devices with broadcast code in this list will be connected. The + * broadcast code is unique for every device. + * @param broadcast_code device's broadcast code. + * @param handle device handle. The handle is the same as the order calling AddLidarToConnect starting from 0. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status AddLidarToConnect(const char *broadcast_code, uint8_t *handle); + +/** + * Get all connected devices' information. + * @param devices list of connected devices' information. + * @param size number of devices connected. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status GetConnectedDevices(DeviceInfo *devices, uint8_t *size); + +/** + * Function type of callback that queries device's information. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*DeviceInformationCallback)(livox_status status, + uint8_t handle, + DeviceInformationResponse *response, + void *client_data); + +/** + * Command to query device's information. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status QueryDeviceInformation(uint8_t handle, DeviceInformationCallback cb, void *client_data); + +/** + * Callback function for receiving point cloud data. + * @param handle device handle. + * @param data device's data. + * @param data_num number of points in data. + * @param client_data user data associated with the command. + */ +typedef void (*DataCallback)(uint8_t handle, LivoxEthPacket *data, uint32_t data_num, void *client_data); + +/** + * Set the callback to receive point cloud data. Only one callback is supported for a specific device. Set the point + * cloud data callback before beginning sampling. + * @param handle device handle. + * @param cb callback to receive point cloud data. + * @note 1: Don't do any blocking operations in callback function, it will affects further data's receiving; + * 2: For different device handle, callback to receive point cloud data will run on its own thread. If you bind + * different handle to same callback function, please make sure that operations in callback function are thread-safe; + * 3: callback function's data pointer will be invalid after callback fuction returns. It's recommended to + * copy all data_num of point cloud every time callback is triggered. + * @param client_data user data associated with the command. + */ +void SetDataCallback(uint8_t handle, DataCallback cb, void *client_data); + +/** + * Function type of callback with 1 byte of response. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*CommonCommandCallback)(livox_status status, uint8_t handle, uint8_t response, void *client_data); + +/** + * Start hub sampling. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubStartSampling(CommonCommandCallback cb, void *client_data); + +/** + * Stop the Livox Hub's sampling. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubStopSampling(CommonCommandCallback cb, void *client_data); + +/** + * Get the LiDAR unit handle used in the Livox Hub data callback function from slot and id. + * @param slot Livox Hub's slot. + * @param id Livox Hub's id. + * @return LiDAR unit handle. + */ +uint8_t HubGetLidarHandle(uint8_t slot, uint8_t id); + +/** + * Disconnect divice. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status DisconnectDevice(uint8_t handle, CommonCommandCallback cb, void *client_data); + +/** + * Change point cloud coordinate system to cartesian coordinate. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status SetCartesianCoordinate(uint8_t handle, CommonCommandCallback cb, void *client_data); + +/** + * Change point cloud coordinate system to spherical coordinate. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status SetSphericalCoordinate(uint8_t handle, CommonCommandCallback cb, void *client_data); + +/** + * Callback of the error status message. + * kStatusSuccess on successful return, see \ref LivoxStatus for other + * @param handle device handle. + * @param response response from the device. + */ +typedef void (*ErrorMessageCallback)(livox_status status, uint8_t handle, ErrorMessage *message); + +/** + * Add error status callback for the device. + * error code. + * @param handle device handle. + * @param cb callback for the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status SetErrorMessageCallback(uint8_t handle, ErrorMessageCallback cb); + +/** + * Set device's IP mode. + * @note \ref SetStaticDynamicIP only supports setting Hub or Mid40/100's IP mode. + * If you want to set Horizon or Tele's IP mode, see \ref SetStaticIp and \ref SetDynamicIp. + * @param handle device handle. + * @param req request sent to device. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status SetStaticDynamicIP(uint8_t handle, + SetDeviceIPModeRequest *req, + CommonCommandCallback cb, + void *client_data); +/** + * Set device's static IP mode. + * @note Mid40/100 is not supported to set subnet mask and gateway address. + * \ref SetStaticDeviceIpModeRequest's setting: net_mask and gw_addr will not take effect on Mid40/100. + * @param handle device handle. + * @param req request sent to device. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status SetStaticIp(uint8_t handle, + SetStaticDeviceIpModeRequest *req, + CommonCommandCallback cb, + void *client_data); + +/** + * Set device's dynamic IP mode. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status SetDynamicIp(uint8_t handle, + CommonCommandCallback cb, + void *client_data); +/** + * Callback function that gets device's IP information. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*GetDeviceIpInformationCallback)(livox_status status, + uint8_t handle, + GetDeviceIpModeResponse *response, + void *client_data); + +/** + * Get device's IP mode. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status GetDeviceIpInformation(uint8_t handle, GetDeviceIpInformationCallback cb, void *client_data); + +/** + * Reboot device. + * @note \ref RebootDevice is not supported for Mid40/100 firmware version < 03.07.0000. + * @param handle device handle. + * @param timeout reboot device after [timeout] ms. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status RebootDevice(uint8_t handle, uint16_t timeout, CommonCommandCallback cb, void * client_data); + +/** + * @c SetDeviceParameters' response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*SetDeviceParametersCallback)(livox_status status, + uint8_t handle, + DeviceParameterResponse *response, + void *client_data); + +/** + * LiDAR Enable HighSensitivity. + * @note \ref LidarEnableHighSensitivity only support for Tele/Avia. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarEnableHighSensitivity(uint8_t handle, SetDeviceParametersCallback cb, void *client_data); + +/** + * LiDAR Disable HighSensitivity. + * @note \ref LidarDisableHighSensitivity only support for Tele/Avia. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarDisableHighSensitivity(uint8_t handle, SetDeviceParametersCallback cb, void *client_data); + +/** + * @c GetDeviceParameters' response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*GetDeviceParametersCallback)(livox_status status, + uint8_t handle, + GetDeviceParameterResponse *response, + void *client_data); + +/** + * LiDAR Get HighSensitivity State. + * @note \ref LidarGetHighSensitivityState only support for Tele/Avia. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarGetHighSensitivityState(uint8_t handle, GetDeviceParametersCallback cb, void *client_data); + +/** + * LiDAR Set Scan Pattern. + * @note \ref LidarSetScanPattern only support for Avia. + * @param handle device handle. + * @param pattern scan pattern of LiDAR, see \ref LidarScanPattern for detail. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarSetScanPattern(uint8_t handle, LidarScanPattern pattern, SetDeviceParametersCallback cb, void *client_data); + +/** + * LiDAR Get Scan Pattern. + * @note \ref LidarGetScanPattern only support for Avia. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarGetScanPattern(uint8_t handle, GetDeviceParametersCallback cb, void *client_data); + +/** + * LiDAR Set Slot Number. + * @note \ref LidarSetSlotNum only support for Mid70/Avia. + * @param handle device handle. + * @param slot slot number of LiDAR, range from 1 to 9. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarSetSlotNum(uint8_t handle, uint8_t slot, SetDeviceParametersCallback cb, void *client_data); + +/** + * LiDAR Get Slot Number. + * @note \ref LidarGetSlotNum only support for Mid70/Avia. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarGetSlotNum(uint8_t handle, GetDeviceParametersCallback cb, void *client_data); + +/** + * @c DeviceResetParameters' response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*DeviceResetParametersCallback)(livox_status status, + uint8_t handle, + DeviceParameterResponse *response, + void *client_data); + +/** + * Reset LiDAR/Hub's All Parameters, see \ref DeviceParamKeyName for all parameters. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status DeviceResetAllParameters(uint8_t handle, DeviceResetParametersCallback cb, void *client_data); + +/** + * Reset LiDAR/Hub's Parameters, see \ref DeviceParamKeyName for all parameters. + * @param handle device handle. + * @param keys keys to reset, see \ref DeviceParamKeyName for all parameters. + * @param num num of keys to reset. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status DeviceResetParameters(uint8_t handle, DeviceParamKeyName * keys, uint8_t num, DeviceResetParametersCallback cb, void *client_data); + + +/** + * @c HubQueryLidarInformation response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*HubQueryLidarInformationCallback)(livox_status status, + uint8_t handle, + HubQueryLidarInformationResponse *response, + void *client_data); + +/** + * Query the information of LiDARs connected to the hub. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubQueryLidarInformation(HubQueryLidarInformationCallback cb, void *client_data); + +/** + * @c HubSetMode response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*HubSetModeCallback)(livox_status status, uint8_t handle, HubSetModeResponse *response, void *client_data); + +/** + * Set the mode of LiDAR unit connected to the Livox Hub. + * @param req mode configuration of LiDAR units. + * @param length length of req. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubSetMode(HubSetModeRequest *req, uint16_t length, HubSetModeCallback cb, void *client_data); + +/** + * @c HubQueryLidarStatus response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*HubQueryLidarStatusCallback)(livox_status status, uint8_t handle, HubQueryLidarStatusResponse *response, void *client_data); + +/** + * Get the state of LiDAR units connected to the Livox Hub. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubQueryLidarStatus(HubQueryLidarStatusCallback cb, void *client_data); + +/** + * Toggle the power supply of designated slots. + * @param req request whether to enable or disable the power of designated slots. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubControlSlotPower(HubControlSlotPowerRequest *req, CommonCommandCallback cb, void *client_data); + +/** + * @c HubSetExtrinsicParameter response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*HubSetExtrinsicParameterCallback)(livox_status status, + uint8_t handle, + HubSetExtrinsicParameterResponse *response, + void *client_data); + +/** + * Set extrinsic parameters of LiDAR units connected to the Livox Hub. + * @param req the parameters to write. + * @param length the request's length. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubSetExtrinsicParameter(HubSetExtrinsicParameterRequest *req, + uint16_t length, + HubSetExtrinsicParameterCallback cb, + void *client_data); + +/** + * @c HubGetExtrinsicParameter response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*HubGetExtrinsicParameterCallback)(livox_status status, + uint8_t handle, + HubGetExtrinsicParameterResponse *response, + void *client_data); + +/** + * Get extrinsic parameters of LiDAR units connected to the Livox Hub. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubGetExtrinsicParameter(HubGetExtrinsicParameterCallback cb, void *client_data); + +/** + * Turn on or off the calculation of extrinsic parameters. + * @param enable the request whether enable or disable calculating the extrinsic parameters. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubExtrinsicParameterCalculation(bool enable, CommonCommandCallback cb, void *client_data); + +/** + * @c HubRainFogSuppress response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*HubRainFogSuppressCallback)(livox_status status, + uint8_t handle, + HubRainFogSuppressResponse *response, + void *client_data); + +/** + * Toggling the rain and fog mode for lidars connected to the hub. + * @param req the request whether open or close the rain and fog mode. + * @param length the request's length. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubRainFogSuppress(HubRainFogSuppressRequest *req, + uint16_t length, + HubRainFogSuppressCallback cb, + void *client_data); + +/** +* @c HubQuerySlotPowerStatus response callback function. +* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other +* error code. +* @param handle device handle. +* @param response response from the device. +* @param client_data user data associated with the command. +*/ +typedef void(*HubQuerySlotPowerStatusCallback)(livox_status status, uint8_t handle, HubQuerySlotPowerStatusResponse *response, void *client_data); + +/** +* Get the power supply state of each hub slot. +* @param cb callback for the command. +* @param client_data user data associated with the command. +* @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. +*/ +livox_status HubQuerySlotPowerStatus(HubQuerySlotPowerStatusCallback cb, void *client_data); + +/** +* @c HubFanControl response callback function. +* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other +* error code. +* @param handle device handle. +* @param response response from the device. +* @param client_data user data associated with the command. +*/ +typedef void (*HubFanControlCallback)(livox_status status, + uint8_t handle, + HubFanControlResponse *response, + void *client_data); + +/** + * Turn on or off the fan of LiDAR unit connected to the Livox Hub. + * @param req Fan control of LiDAR units. + * @param length length of req. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubFanControl(HubFanControlRequest *req, uint16_t length, HubFanControlCallback cb, void *client_data); + +/** +* @c HubGetFanControl response callback function. +* @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other +* error code. +* @param handle device handle. +* @param response response from the device. +* @param client_data user data associated with the command. +*/ +typedef void (*HubGetFanStateCallback)(livox_status status, + uint8_t handle, + HubGetFanStateResponse *response, + void *client_data); + +/** + * Get fan state of LiDAR unit connected to the Livox Hub. + * @param req Get fan state of LiDAR units. + * @param length length of req. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubGetFanState(HubGetFanStateRequest *req, + uint16_t length, + HubGetFanStateCallback cb, + void *client_data); + +/** + * @c HubSetPointCloudReturnMode response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*HubSetPointCloudReturnModeCallback)(livox_status status, + uint8_t handle, + HubSetPointCloudReturnModeResponse *response, + void *client_data); + +/** + * Set point cloud return mode of LiDAR units connected to the Livox Hub. + * @param req set point cloud return mode of LiDAR units. + * @param length the request's length. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubSetPointCloudReturnMode(HubSetPointCloudReturnModeRequest *req, + uint16_t length, + HubSetPointCloudReturnModeCallback cb, + void *client_data); + +/** + * @c HubGetPointCloudReturnMode response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*HubGetPointCloudReturnModeCallback)(livox_status status, + uint8_t handle, + HubGetPointCloudReturnModeResponse *response, + void *client_data); + +/** + * Get point cloud return mode of LiDAR unit connected to the Livox Hub. + * @param req Get point cloud return mode of LiDAR units. + * @param length length of req. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubGetPointCloudReturnMode(HubGetPointCloudReturnModeRequest *req, + uint16_t length, + HubGetPointCloudReturnModeCallback cb, + void *client_data); + +/** + * @c HubSetImuPushFrequency response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*HubSetImuPushFrequencyCallback)(livox_status status, + uint8_t handle, + HubSetImuPushFrequencyResponse *response, + void *client_data); + +/** + * Set IMU push frequency of LiDAR units connected to the Livox Hub. + * @param req set IMU push frequency of LiDAR units. + * @param length the request's length. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubSetImuPushFrequency(HubSetImuPushFrequencyRequest *req, + uint16_t length, + HubSetImuPushFrequencyCallback cb, + void *client_data); + +/** + * @c HubGetImuPushFrequency response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*HubGetImuPushFrequencyCallback)(livox_status status, + uint8_t handle, + HubGetImuPushFrequencyResponse *response, + void *client_data); + +/** + * Get IMU push frequency of LiDAR units connected to the Livox Hub. + * @param req get IMU push frequency of LiDAR units. + * @param length the request's length. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status HubGetImuPushFrequency(HubGetImuPushFrequencyRequest *req, + uint16_t length, + HubGetImuPushFrequencyCallback cb, + void *client_data); + +/** + * Start LiDAR sampling. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarStartSampling(uint8_t handle, CommonCommandCallback cb, void *client_data); + +/** + * Stop LiDAR sampling. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarStopSampling(uint8_t handle, CommonCommandCallback cb, void *client_data); + +/** + * Set LiDAR mode. + * @note Successful callback function status only means LiDAR successfully starting the changing process of mode. + * You need to observe the actually change of mode in DeviceStateUpdateCallback function. + * @param handle device handle. + * @param mode the mode to change. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarSetMode(uint8_t handle, LidarMode mode, CommonCommandCallback cb, void *client_data); + +/** + * Set LiDAR extrinsic parameters. + * @param handle device handle. + * @param req the parameters to write. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarSetExtrinsicParameter(uint8_t handle, + LidarSetExtrinsicParameterRequest *req, + CommonCommandCallback cb, + void *client_data); + +/** + * @c LidarGetExtrinsicParameter response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*LidarGetExtrinsicParameterCallback)(livox_status status, + uint8_t handle, + LidarGetExtrinsicParameterResponse *response, + void *client_data); + +/** + * Get LiDAR extrinsic parameters. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarGetExtrinsicParameter(uint8_t handle, LidarGetExtrinsicParameterCallback cb, void *client_data); + +/** + * Enable and disable the rain/fog suppression. + * @note \ref LidarRainFogSuppress only support for Mid40/100. + * @param handle device handle. + * @param enable enable and disable the rain/fog suppression. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarRainFogSuppress(uint8_t handle, bool enable, CommonCommandCallback cb, void *client_data); + +/** + * Turn off the fan. + * @note \ref LidarTurnOffFan is not supported for Mid40/100. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarTurnOffFan(uint8_t handle, CommonCommandCallback cb, void *client_data); + +/** + * Turn on the fan. + * @note \ref LidarTurnOnFan is not supported for Mid40/100. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarTurnOnFan(uint8_t handle, CommonCommandCallback cb, void *client_data); + +/** + * @c LidarGetFanState response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*LidarGetFanStateCallback)(livox_status status, + uint8_t handle, + LidarGetFanStateResponse *response, + void *client_data); + +/** + * Get state of the fan. + * @note \ref LidarGetFanState is not supported for Mid40/100. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarGetFanState(uint8_t handle, LidarGetFanStateCallback cb, void * client_data) ; + +/** + * Set point cloud return mode. + * @note \ref LidarSetPointCloudReturnMode is not supported for Mid40/100. + * @param handle device handle. + * @param mode point cloud return mode. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarSetPointCloudReturnMode(uint8_t handle, PointCloudReturnMode mode, CommonCommandCallback cb, void * client_data); + +/** + * @c LidaGetPointCloudReturnMode response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*LidarGetPointCloudReturnModeCallback)(livox_status status, + uint8_t handle, + LidarGetPointCloudReturnModeResponse *response, + void *client_data); + +/** + * Get point cloud return mode. + * @note \ref LidarGetPointCloudReturnMode is not supported for Mid40/100. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarGetPointCloudReturnMode(uint8_t handle, LidarGetPointCloudReturnModeCallback cb, void * client_data); + +/** + * Set IMU push frequency. + * @note \ref LidarSetImuPushFrequency is not supported for Mid40/100. + * @param handle device handle. + * @param freq IMU push frequency. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarSetImuPushFrequency(uint8_t handle, ImuFreq freq, CommonCommandCallback cb, void * client_data); + +/** + * @c LidaGetImuPushFrequency response callback function. + * @param status kStatusSuccess on successful return, kStatusTimeout on timeout, see \ref LivoxStatus for other + * error code. + * @param handle device handle. + * @param response response from the device. + * @param client_data user data associated with the command. + */ +typedef void (*LidarGetImuPushFrequencyCallback)(livox_status status, + uint8_t handle, + LidarGetImuPushFrequencyResponse *response, + void *client_data); + +/** + * Get IMU push frequency. + * @note \ref LidarGetImuPushFrequency is not supported for Mid40/100. + * @param handle device handle. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarGetImuPushFrequency(uint8_t handle, LidarGetImuPushFrequencyCallback cb, void * client_data); + +/** + * Set GPRMC formate synchronization time. + * @note \ref LidarSetRmcSyncTime is not supported for Mid40/100 firmware version < 03.07.0000. + * @param handle device handle. + * @param rmc GPRMC/GNRMC format data. + * @param rmc_length lenth of gprmc. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarSetRmcSyncTime(uint8_t handle, + const char* rmc, + uint16_t rmc_length, + CommonCommandCallback cb, + void *client_data); + +/** + * Set UTC formate synchronization time. + * @note \ref LidarSetUtcSyncTime is not supported for Mid40/100 firmware version < 03.07.0000. + * @param handle device handle. + * @param req UTC format data. + * @param cb callback for the command. + * @param client_data user data associated with the command. + * @return kStatusSuccess on successful return, see \ref LivoxStatus for other error code. + */ +livox_status LidarSetUtcSyncTime(uint8_t handle, + LidarSetUtcSyncTimeRequest* req, + CommonCommandCallback cb, + void *client_data); + +#ifdef __cplusplus +} +#endif + +#endif // LIVOX_SDK_H_ diff --git a/lidar_driver/include/Livox/third_party/FastCRC/FastCRC.h b/lidar_driver/include/Livox/third_party/FastCRC/FastCRC.h new file mode 100644 index 0000000..d796171 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/FastCRC/FastCRC.h @@ -0,0 +1,79 @@ +/* FastCRC library code is placed under the MIT license + * Copyright (c) 2014,2015 Frank Bosing + * + * Permission is hereby granted, free of charge, to any person obtaining + * a copy of this software and associated documentation files (the + * "Software"), to deal in the Software without restriction, including + * without limitation the rights to use, copy, modify, merge, publish, + * distribute, sublicense, and/or sell copies of the Software, and to + * permit persons to whom the Software is furnished to do so, subject to + * the following conditions: + * + * The above copyright notice and this permission notice shall be + * included in all copies or substantial portions of the Software. + * + * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, + * EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF + * MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + * NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS + * BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN + * ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN + * CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE + * SOFTWARE. + */ + + +// Teensy 3.0, Teensy 3.1: +// See K20P64M72SF1RM.pdf (Kinetis), Pages 638 - 641 for documentation of CRC Device +// See KINETIS_4N30D.pdf for Errata (Errata ID 2776) +// +// So, ALL HW-calculations are done as 32 bit. +// +// +// +// Thanks to: +// - Catalogue of parametrised CRC algorithms, CRC RevEng +// http://reveng.sourceforge.net/crc-catalogue/ +// +// - Danjel McGougan (CRC-Table-Generator) +// + +// +// modify from FastCRC library @ 2018/11/20 +// + +#ifndef FASTCRC_FASTCRC_H_ +#define FASTCRC_FASTCRC_H_ + +#include + + +// ================= 16-BIT CRC =================== + +class FastCRC16 { +public: + FastCRC16(uint16_t seed); + + // change function name from mcrf4xx_upd to mcrf4xx + uint16_t mcrf4xx_calc(const uint8_t *data,const uint16_t datalen); // Equivalent to _crc_ccitt_update() in crc16.h from avr_libc + +private: + uint16_t seed_; + +}; + +// ================= 32-BIT CRC =================== + +class FastCRC32 { +public: + FastCRC32(uint32_t seed); + + // change function name from crc32_upd to crc32 + uint32_t crc32_calc(const uint8_t *data, uint16_t len); // Call for subsequent calculations with previous seed + +private: + uint32_t seed_; +}; + +#endif // FASTCRC_FASTCRC_H_ + diff --git a/lidar_driver/include/Livox/third_party/cmdline/cmdline.h b/lidar_driver/include/Livox/third_party/cmdline/cmdline.h new file mode 100644 index 0000000..f3d7eee --- /dev/null +++ b/lidar_driver/include/Livox/third_party/cmdline/cmdline.h @@ -0,0 +1,823 @@ +/* + Copyright (c) 2009, Hideyuki Tanaka + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + * Redistributions of source code must retain the above copyright + notice, this list of conditions and the following disclaimer. + * Redistributions in binary form must reproduce the above copyright + notice, this list of conditions and the following disclaimer in the + documentation and/or other materials provided with the distribution. + * Neither the name of the nor the + names of its contributors may be used to endorse or promote products + derived from this software without specific prior written permission. + + THIS SOFTWARE IS PROVIDED BY ''AS IS'' AND ANY + EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL BE LIABLE FOR ANY + DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. +*/ + +#pragma once + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#if defined(_MSC_VER) +#include +#include +#undef max +#pragma comment(lib, "dbghelp.lib") +#elif defined(__clang__) || defined(__GNUC__) +#include +#endif +#include + +namespace cmdline{ + +namespace detail{ + +template +class lexical_cast_t{ +public: + static Target cast(const Source &arg){ + Target ret; + std::stringstream ss; + if (!(ss<>ret && ss.eof())) + throw std::bad_cast(); + + return ret; + } +}; + +template +class lexical_cast_t{ +public: + static Target cast(const Source &arg){ + return arg; + } +}; + +template +class lexical_cast_t{ +public: + static std::string cast(const Source &arg){ + std::ostringstream ss; + ss< +class lexical_cast_t{ +public: + static Target cast(const std::string &arg){ + Target ret; + std::istringstream ss(arg); + if (!(ss>>ret && ss.eof())) + throw std::bad_cast(); + return ret; + } +}; + +template +struct is_same { + static const bool value = false; +}; + +template +struct is_same{ + static const bool value = true; +}; + +template +Target lexical_cast(const Source &arg) +{ + return lexical_cast_t::value>::cast(arg); +} + +static inline std::string demangle(const std::string &name) +{ +#if defined(_MSC_VER) + TCHAR ret[256]; + std::memset(ret, 0, 256); + ::UnDecorateSymbolName(name.c_str(), ret, 256, 0); + return ret; +#else + int status=0; + char *p=abi::__cxa_demangle(name.c_str(), 0, 0, &status); + std::string ret(p); + free(p); + return ret; +#endif +} + +template +std::string readable_typename() +{ + return demangle(typeid(T).name()); +} + +template +std::string default_value(T def) +{ + return detail::lexical_cast(def); +} + +template <> +inline std::string readable_typename() +{ + return "string"; +} + +} // detail + +//----- + +class cmdline_error : public std::exception { +public: + cmdline_error(const std::string &msg): msg(msg){} + ~cmdline_error() throw() {} + const char *what() const throw() { return msg.c_str(); } +private: + std::string msg; +}; + +template +struct default_reader{ + T operator()(const std::string &str){ + return detail::lexical_cast(str); + } +}; + +template +struct range_reader{ + range_reader(const T &low, const T &high): low(low), high(high) {} + T operator()(const std::string &s) const { + T ret=default_reader()(s); + if (!(ret>=low && ret<=high)) throw cmdline::cmdline_error("range_error"); + return ret; + } +private: + T low, high; +}; + +template +range_reader range(const T &low, const T &high) +{ + return range_reader(low, high); +} + +template +struct oneof_reader{ + T operator()(const std::string &s){ + T ret=default_reader()(s); + if (std::find(alt.begin(), alt.end(), ret)==alt.end()) + throw cmdline_error(""); + return ret; + } + void add(const T &v){ alt.push_back(v); } +private: + std::vector alt; +}; + +template +oneof_reader oneof(T a1) +{ + oneof_reader ret; + ret.add(a1); + return ret; +} + +template +oneof_reader oneof(T a1, T a2) +{ + oneof_reader ret; + ret.add(a1); + ret.add(a2); + return ret; +} + +template +oneof_reader oneof(T a1, T a2, T a3) +{ + oneof_reader ret; + ret.add(a1); + ret.add(a2); + ret.add(a3); + return ret; +} + +template +oneof_reader oneof(T a1, T a2, T a3, T a4) +{ + oneof_reader ret; + ret.add(a1); + ret.add(a2); + ret.add(a3); + ret.add(a4); + return ret; +} + +template +oneof_reader oneof(T a1, T a2, T a3, T a4, T a5) +{ + oneof_reader ret; + ret.add(a1); + ret.add(a2); + ret.add(a3); + ret.add(a4); + ret.add(a5); + return ret; +} + +template +oneof_reader oneof(T a1, T a2, T a3, T a4, T a5, T a6) +{ + oneof_reader ret; + ret.add(a1); + ret.add(a2); + ret.add(a3); + ret.add(a4); + ret.add(a5); + ret.add(a6); + return ret; +} + +template +oneof_reader oneof(T a1, T a2, T a3, T a4, T a5, T a6, T a7) +{ + oneof_reader ret; + ret.add(a1); + ret.add(a2); + ret.add(a3); + ret.add(a4); + ret.add(a5); + ret.add(a6); + ret.add(a7); + return ret; +} + +template +oneof_reader oneof(T a1, T a2, T a3, T a4, T a5, T a6, T a7, T a8) +{ + oneof_reader ret; + ret.add(a1); + ret.add(a2); + ret.add(a3); + ret.add(a4); + ret.add(a5); + ret.add(a6); + ret.add(a7); + ret.add(a8); + return ret; +} + +template +oneof_reader oneof(T a1, T a2, T a3, T a4, T a5, T a6, T a7, T a8, T a9) +{ + oneof_reader ret; + ret.add(a1); + ret.add(a2); + ret.add(a3); + ret.add(a4); + ret.add(a5); + ret.add(a6); + ret.add(a7); + ret.add(a8); + ret.add(a9); + return ret; +} + +template +oneof_reader oneof(T a1, T a2, T a3, T a4, T a5, T a6, T a7, T a8, T a9, T a10) +{ + oneof_reader ret; + ret.add(a1); + ret.add(a2); + ret.add(a3); + ret.add(a4); + ret.add(a5); + ret.add(a6); + ret.add(a7); + ret.add(a8); + ret.add(a9); + ret.add(a10); + return ret; +} + +//----- + +class parser{ +public: + parser(){ + } + ~parser(){ + for (std::map::iterator p=options.begin(); + p!=options.end(); p++) + delete p->second; + } + + void add(const std::string &name, + char short_name=0, + const std::string &desc=""){ + if (options.count(name)) throw cmdline_error("multiple definition: "+name); + options[name]=new option_without_value(name, short_name, desc); + ordered.push_back(options[name]); + } + + template + void add(const std::string &name, + char short_name=0, + const std::string &desc="", + bool need=true, + const T def=T()){ + add(name, short_name, desc, need, def, default_reader()); + } + + template + void add(const std::string &name, + char short_name=0, + const std::string &desc="", + bool need=true, + const T def=T(), + F reader=F()){ + if (options.count(name)) throw cmdline_error("multiple definition: "+name); + options[name]=new option_with_value_with_reader(name, short_name, need, def, desc, reader); + ordered.push_back(options[name]); + } + + void footer(const std::string &f){ + ftr=f; + } + + void set_program_name(const std::string &name){ + prog_name=name; + } + + bool exist(const std::string &name) const { + if (options.count(name)==0) throw cmdline_error("there is no flag: --"+name); + return options.find(name)->second->has_set(); + } + + template + const T &get(const std::string &name) const { + if (options.count(name)==0) throw cmdline_error("there is no flag: --"+name); + const option_with_value *p=dynamic_cast*>(options.find(name)->second); + if (p==NULL) throw cmdline_error("type mismatch flag '"+name+"'"); + return p->get(); + } + + const std::vector &rest() const { + return others; + } + + bool parse(const std::string &arg){ + std::vector args; + + std::string buf; + bool in_quote=false; + for (std::string::size_type i=0; i=arg.length()){ + errors.push_back("unexpected occurrence of '\\' at end of string"); + return false; + } + } + + buf+=arg[i]; + } + + if (in_quote){ + errors.push_back("quote is not closed"); + return false; + } + + if (buf.length()>0) + args.push_back(buf); + + for (size_t i=0; i &args){ + int argc=static_cast(args.size()); + std::vector argv(argc); + + for (int i=0; i lookup; + for (std::map::iterator p=options.begin(); + p!=options.end(); p++){ + if (p->first.length()==0) continue; + char initial=p->second->short_name(); + if (initial){ + if (lookup.count(initial)>0){ + lookup[initial]=""; + errors.push_back(std::string("short option '")+initial+"' is ambiguous"); + return false; + } + else lookup[initial]=p->first; + } + } + + for (int i=1; i &args){ + if (!options.count("help")) + add("help", '?', "print this message"); + check(args.size(), parse(args)); + } + + void parse_check(int argc, char *argv[]){ + if (!options.count("help")) + add("help", '?', "print this message"); + check(argc, parse(argc, argv)); + } + + std::string error() const{ + return errors.size()>0?errors[0]:""; + } + + std::string error_full() const{ + std::ostringstream oss; + for (size_t i=0; imust()) + oss<short_description()<<" "; + } + + oss<<"[options] ... "<name().length()); + } + for (size_t i=0; ishort_name()){ + oss<<" -"<short_name()<<", "; + } + else{ + oss<<" "; + } + + oss<<"--"<name(); + for (size_t j=ordered[i]->name().length(); jdescription()<set()){ + errors.push_back("option needs value: --"+name); + return; + } + } + + void set_option(const std::string &name, const std::string &value){ + if (options.count(name)==0){ + errors.push_back("undefined option: --"+name); + return; + } + if (!options[name]->set(value)){ + errors.push_back("option value is invalid: --"+name+"="+value); + return; + } + } + + class option_base{ + public: + virtual ~option_base(){} + + virtual bool has_value() const=0; + virtual bool set()=0; + virtual bool set(const std::string &value)=0; + virtual bool has_set() const=0; + virtual bool valid() const=0; + virtual bool must() const=0; + + virtual const std::string &name() const=0; + virtual char short_name() const=0; + virtual const std::string &description() const=0; + virtual std::string short_description() const=0; + }; + + class option_without_value : public option_base { + public: + option_without_value(const std::string &name, + char short_name, + const std::string &desc) + :nam(name), snam(short_name), desc(desc), has(false){ + } + ~option_without_value(){} + + bool has_value() const { return false; } + + bool set(){ + has=true; + return true; + } + + bool set(const std::string &){ + return false; + } + + bool has_set() const { + return has; + } + + bool valid() const{ + return true; + } + + bool must() const{ + return false; + } + + const std::string &name() const{ + return nam; + } + + char short_name() const{ + return snam; + } + + const std::string &description() const { + return desc; + } + + std::string short_description() const{ + return "--"+nam; + } + + private: + std::string nam; + char snam; + std::string desc; + bool has; + }; + + template + class option_with_value : public option_base { + public: + option_with_value(const std::string &name, + char short_name, + bool need, + const T &def, + const std::string &desc) + : nam(name), snam(short_name), need(need), has(false) + , def(def), actual(def) { + this->desc=full_description(desc); + } + ~option_with_value(){} + + const T &get() const { + return actual; + } + + bool has_value() const { return true; } + + bool set(){ + return false; + } + + bool set(const std::string &value){ + try{ + actual=read(value); + has=true; + } + catch(const std::exception &){ + return false; + } + return true; + } + + bool has_set() const{ + return has; + } + + bool valid() const{ + if (need && !has) return false; + return true; + } + + bool must() const{ + return need; + } + + const std::string &name() const{ + return nam; + } + + char short_name() const{ + return snam; + } + + const std::string &description() const { + return desc; + } + + std::string short_description() const{ + return "--"+nam+"="+detail::readable_typename(); + } + + protected: + std::string full_description(const std::string &desc){ + return + desc+" ("+detail::readable_typename()+ + (need?"":" [="+detail::default_value(def)+"]") + +")"; + } + + virtual T read(const std::string &s)=0; + + std::string nam; + char snam; + bool need; + std::string desc; + + bool has; + T def; + T actual; + }; + + template + class option_with_value_with_reader : public option_with_value { + public: + option_with_value_with_reader(const std::string &name, + char short_name, + bool need, + const T def, + const std::string &desc, + F reader) + : option_with_value(name, short_name, need, def, desc), reader(reader){ + } + + private: + T read(const std::string &s){ + return reader(s); + } + + F reader; + }; + + std::map options; + std::vector ordered; + std::string ftr; + + std::string prog_name; + std::vector others; + + std::vector errors; +}; + +} // cmdline diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/async.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/async.h new file mode 100644 index 0000000..971becd --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/async.h @@ -0,0 +1,87 @@ + +// +// Copyright(c) 2018 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +// +// Async logging using global thread pool +// All loggers created here share same global thread pool. +// Each log message is pushed to a queue along withe a shared pointer to the +// logger. +// If a logger deleted while having pending messages in the queue, it's actual +// destruction will defer +// until all its messages are processed by the thread pool. +// This is because each message in the queue holds a shared_ptr to the +// originating logger. + +#include "spdlog/async_logger.h" +#include "spdlog/details/registry.h" +#include "spdlog/details/thread_pool.h" + +#include +#include + +namespace spdlog { + +namespace details { +static const size_t default_async_q_size = 8192; +} + +// async logger factory - creates async loggers backed with thread pool. +// if a global thread pool doesn't already exist, create it with default queue +// size of 8192 items and single thread. +template +struct async_factory_impl +{ + template + static std::shared_ptr create(std::string logger_name, SinkArgs &&... args) + { + auto ®istry_inst = details::registry::instance(); + + // create global thread pool if not already exists.. + std::lock_guard tp_lock(registry_inst.tp_mutex()); + auto tp = registry_inst.get_tp(); + if (tp == nullptr) + { + tp = std::make_shared(details::default_async_q_size, 1); + registry_inst.set_tp(tp); + } + + auto sink = std::make_shared(std::forward(args)...); + auto new_logger = std::make_shared(std::move(logger_name), std::move(sink), std::move(tp), OverflowPolicy); + registry_inst.initialize_logger(new_logger); + return new_logger; + } +}; + +using async_factory = async_factory_impl; +using async_factory_nonblock = async_factory_impl; + +template +inline std::shared_ptr create_async(std::string logger_name, SinkArgs &&... sink_args) +{ + return async_factory::create(std::move(logger_name), std::forward(sink_args)...); +} + +template +inline std::shared_ptr create_async_nb(std::string logger_name, SinkArgs &&... sink_args) +{ + return async_factory_nonblock::create(std::move(logger_name), std::forward(sink_args)...); +} + +// set global thread pool. +inline void init_thread_pool(size_t q_size, size_t thread_count) +{ + auto tp = std::make_shared(q_size, thread_count); + details::registry::instance().set_tp(std::move(tp)); +} + +// get the global thread pool. +inline std::shared_ptr thread_pool() +{ + return details::registry::instance().get_tp(); +} +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/async_logger.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/async_logger.h new file mode 100644 index 0000000..a7ecb78 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/async_logger.h @@ -0,0 +1,73 @@ +// +// Copyright(c) 2015 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +// Very fast asynchronous logger (millions of logs per second on an average +// desktop) +// Uses pre allocated lockfree queue for maximum throughput even under large +// number of threads. +// Creates a single back thread to pop messages from the queue and log them. +// +// Upon each log write the logger: +// 1. Checks if its log level is enough to log the message +// 2. Push a new copy of the message to a queue (or block the caller until +// space is available in the queue) +// 3. will throw spdlog_ex upon log exceptions +// Upon destruction, logs all remaining messages in the queue before +// destructing.. + +#include "spdlog/common.h" +#include "spdlog/logger.h" + +#include +#include +#include + +namespace spdlog { + +// Async overflow policy - block by default. +enum class async_overflow_policy +{ + block, // Block until message can be enqueued + overrun_oldest // Discard oldest message in the queue if full when trying to + // add new item. +}; + +namespace details { +class thread_pool; +} + +class async_logger final : public std::enable_shared_from_this, public logger +{ + friend class details::thread_pool; + +public: + template + async_logger(std::string logger_name, It begin, It end, std::weak_ptr tp, + async_overflow_policy overflow_policy = async_overflow_policy::block); + + async_logger(std::string logger_name, sinks_init_list sinks_list, std::weak_ptr tp, + async_overflow_policy overflow_policy = async_overflow_policy::block); + + async_logger(std::string logger_name, sink_ptr single_sink, std::weak_ptr tp, + async_overflow_policy overflow_policy = async_overflow_policy::block); + + std::shared_ptr clone(std::string new_name) override; + +protected: + void sink_it_(details::log_msg &msg) override; + void flush_() override; + + void backend_log_(const details::log_msg &incoming_log_msg); + void backend_flush_(); + +private: + std::weak_ptr thread_pool_; + async_overflow_policy overflow_policy_; +}; +} // namespace spdlog + +#include "details/async_logger_impl.h" diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/common.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/common.h new file mode 100644 index 0000000..dd9a478 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/common.h @@ -0,0 +1,246 @@ +// +// Copyright(c) 2015 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +#include "spdlog/tweakme.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#if defined(SPDLOG_WCHAR_FILENAMES) || defined(SPDLOG_WCHAR_TO_UTF8_SUPPORT) +#include +#include +#endif + +#include "spdlog/details/null_mutex.h" + +#include "spdlog/fmt/fmt.h" + +// visual studio upto 2013 does not support noexcept nor constexpr +#if defined(_MSC_VER) && (_MSC_VER < 1900) +#define SPDLOG_NOEXCEPT throw() +#define SPDLOG_CONSTEXPR +#else +#define SPDLOG_NOEXCEPT noexcept +#define SPDLOG_CONSTEXPR constexpr +#endif + +#if defined(__GNUC__) || defined(__clang__) +#define SPDLOG_DEPRECATED __attribute__((deprecated)) +#elif defined(_MSC_VER) +#define SPDLOG_DEPRECATED __declspec(deprecated) +#else +#define SPDLOG_DEPRECATED +#endif + +// disable thread local on msvc 2013 +#ifndef SPDLOG_NO_TLS +#if (defined(_MSC_VER) && (_MSC_VER < 1900)) || defined(__cplusplus_winrt) +#define SPDLOG_NO_TLS 1 +#endif +#endif + +// Get the basename of __FILE__ (at compile time if possible) +#if FMT_HAS_FEATURE(__builtin_strrchr) +#define SPDLOG_STRRCHR(str, sep) __builtin_strrchr(str, sep) +#else +#define SPDLOG_STRRCHR(str, sep) strrchr(str, sep) +#endif //__builtin_strrchr not defined + +#ifdef _WIN32 +#define SPDLOG_FILE_BASENAME(file) SPDLOG_STRRCHR("\\" file, '\\') + 1 +#else +#define SPDLOG_FILE_BASENAME(file) SPDLOG_STRRCHR("/" file, '/') + 1 +#endif + +#ifndef SPDLOG_FUNCTION +#define SPDLOG_FUNCTION __FUNCTION__ +#endif + +namespace spdlog { + +class formatter; + +namespace sinks { +class sink; +} + +using log_clock = std::chrono::system_clock; +using sink_ptr = std::shared_ptr; +using sinks_init_list = std::initializer_list; +using log_err_handler = std::function; + +// string_view type - either std::string_view or fmt::string_view (pre c++17) +#if defined(FMT_USE_STD_STRING_VIEW) +using string_view_t = std::string_view; +#else +using string_view_t = fmt::string_view; +#endif + +#if defined(SPDLOG_NO_ATOMIC_LEVELS) +using level_t = details::null_atomic_int; +#else +using level_t = std::atomic; +#endif + +#define SPDLOG_LEVEL_TRACE 0 +#define SPDLOG_LEVEL_DEBUG 1 +#define SPDLOG_LEVEL_INFO 2 +#define SPDLOG_LEVEL_WARN 3 +#define SPDLOG_LEVEL_ERROR 4 +#define SPDLOG_LEVEL_CRITICAL 5 +#define SPDLOG_LEVEL_OFF 6 + +#if !defined(SPDLOG_ACTIVE_LEVEL) +#define SPDLOG_ACTIVE_LEVEL SPDLOG_LEVEL_INFO +#endif + +// Log level enum +namespace level { +enum level_enum +{ + trace = SPDLOG_LEVEL_TRACE, + debug = SPDLOG_LEVEL_DEBUG, + info = SPDLOG_LEVEL_INFO, + warn = SPDLOG_LEVEL_WARN, + err = SPDLOG_LEVEL_ERROR, + critical = SPDLOG_LEVEL_CRITICAL, + off = SPDLOG_LEVEL_OFF, +}; + +#if !defined(SPDLOG_LEVEL_NAMES) +#define SPDLOG_LEVEL_NAMES \ + { \ + "trace", "debug", "info", "warning", "error", "critical", "off" \ + } +#endif +static string_view_t level_string_views[] SPDLOG_LEVEL_NAMES; + +#if !defined(SPDLOG_SHORT_LEVEL_NAMES) +#define SPDLOG_SHORT_LEVEL_NAMES {"T", "D", "I", "W", "E", "C", "O"} +#endif +static const char *short_level_names[] SPDLOG_SHORT_LEVEL_NAMES; + +inline string_view_t &to_string_view(spdlog::level::level_enum l) SPDLOG_NOEXCEPT +{ + return level_string_views[l]; +} + +inline const char *to_short_c_str(spdlog::level::level_enum l) SPDLOG_NOEXCEPT +{ + return short_level_names[l]; +} + +inline spdlog::level::level_enum from_str(const std::string &name) SPDLOG_NOEXCEPT +{ + int level = 0; + for (const auto &level_str : level_string_views) + { + if (level_str == name) + { + return static_cast(level); + } + level++; + } + return level::off; +} + +using level_hasher = std::hash; +} // namespace level + +// +// Pattern time - specific time getting to use for pattern_formatter. +// local time by default +// +enum class pattern_time_type +{ + local, // log localtime + utc // log utc +}; + +// +// Log exception +// +class spdlog_ex : public std::exception +{ +public: + explicit spdlog_ex(std::string msg) + : msg_(std::move(msg)) + { + } + + spdlog_ex(const std::string &msg, int last_errno) + { + fmt::memory_buffer outbuf; + fmt::format_system_error(outbuf, last_errno, msg); + msg_ = fmt::to_string(outbuf); + } + + const char *what() const SPDLOG_NOEXCEPT override + { + return msg_.c_str(); + } + +private: + std::string msg_; +}; + +// +// wchar support for windows file names (SPDLOG_WCHAR_FILENAMES must be defined) +// +#if defined(_WIN32) && defined(SPDLOG_WCHAR_FILENAMES) +using filename_t = std::wstring; +#else +using filename_t = std::string; +#endif + +struct source_loc +{ + SPDLOG_CONSTEXPR source_loc() + : filename{""} + , line{0} + , funcname{""} + { + } + SPDLOG_CONSTEXPR source_loc(const char *filename_in, int line_in, const char *funcname_in) + : filename{filename_in} + , line{static_cast(line_in)} + , funcname{funcname_in} + { + } + + SPDLOG_CONSTEXPR bool empty() const SPDLOG_NOEXCEPT + { + return line == 0; + } + const char *filename; + uint32_t line; + const char *funcname; +}; + +namespace details { +// make_unique support for pre c++14 + +#if __cplusplus >= 201402L // C++14 and beyond +using std::make_unique; +#else +template +std::unique_ptr make_unique(Args &&... args) +{ + static_assert(!std::is_array::value, "arrays not supported"); + return std::unique_ptr(new T(std::forward(args)...)); +} +#endif +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/async_logger_impl.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/async_logger_impl.h new file mode 100644 index 0000000..aafcae6 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/async_logger_impl.h @@ -0,0 +1,110 @@ +// +// Copyright(c) 2015 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +// async logger implementation +// uses a thread pool to perform the actual logging + +#include "spdlog/details/thread_pool.h" + +#include +#include +#include + +template +inline spdlog::async_logger::async_logger( + std::string logger_name, It begin, It end, std::weak_ptr tp, async_overflow_policy overflow_policy) + : logger(std::move(logger_name), begin, end) + , thread_pool_(std::move(tp)) + , overflow_policy_(overflow_policy) +{ +} + +inline spdlog::async_logger::async_logger( + std::string logger_name, sinks_init_list sinks_list, std::weak_ptr tp, async_overflow_policy overflow_policy) + : async_logger(std::move(logger_name), sinks_list.begin(), sinks_list.end(), std::move(tp), overflow_policy) +{ +} + +inline spdlog::async_logger::async_logger( + std::string logger_name, sink_ptr single_sink, std::weak_ptr tp, async_overflow_policy overflow_policy) + : async_logger(std::move(logger_name), {std::move(single_sink)}, std::move(tp), overflow_policy) +{ +} + +// send the log message to the thread pool +inline void spdlog::async_logger::sink_it_(details::log_msg &msg) +{ +#if defined(SPDLOG_ENABLE_MESSAGE_COUNTER) + incr_msg_counter_(msg); +#endif + if (auto pool_ptr = thread_pool_.lock()) + { + pool_ptr->post_log(shared_from_this(), msg, overflow_policy_); + } + else + { + throw spdlog_ex("async log: thread pool doesn't exist anymore"); + } +} + +// send flush request to the thread pool +inline void spdlog::async_logger::flush_() +{ + if (auto pool_ptr = thread_pool_.lock()) + { + pool_ptr->post_flush(shared_from_this(), overflow_policy_); + } + else + { + throw spdlog_ex("async flush: thread pool doesn't exist anymore"); + } +} + +// +// backend functions - called from the thread pool to do the actual job +// +inline void spdlog::async_logger::backend_log_(const details::log_msg &incoming_log_msg) +{ + try + { + for (auto &s : sinks_) + { + if (s->should_log(incoming_log_msg.level)) + { + s->log(incoming_log_msg); + } + } + } + SPDLOG_CATCH_AND_HANDLE + + if (should_flush_(incoming_log_msg)) + { + backend_flush_(); + } +} + +inline void spdlog::async_logger::backend_flush_() +{ + try + { + for (auto &sink : sinks_) + { + sink->flush(); + } + } + SPDLOG_CATCH_AND_HANDLE +} + +inline std::shared_ptr spdlog::async_logger::clone(std::string new_name) +{ + auto cloned = std::make_shared(std::move(new_name), sinks_.begin(), sinks_.end(), thread_pool_, overflow_policy_); + + cloned->set_level(this->level()); + cloned->flush_on(this->flush_level()); + cloned->set_error_handler(this->error_handler()); + return std::move(cloned); +} diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/circular_q.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/circular_q.h new file mode 100644 index 0000000..b01325b --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/circular_q.h @@ -0,0 +1,72 @@ +// +// Copyright(c) 2018 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +// cirucal q view of std::vector. +#pragma once + +#include + +namespace spdlog { +namespace details { +template +class circular_q +{ +public: + using item_type = T; + + explicit circular_q(size_t max_items) + : max_items_(max_items + 1) // one item is reserved as marker for full q + , v_(max_items_) + { + } + + // push back, overrun (oldest) item if no room left + void push_back(T &&item) + { + v_[tail_] = std::move(item); + tail_ = (tail_ + 1) % max_items_; + + if (tail_ == head_) // overrun last item if full + { + head_ = (head_ + 1) % max_items_; + ++overrun_counter_; + } + } + + // Pop item from front. + // If there are no elements in the container, the behavior is undefined. + void pop_front(T &popped_item) + { + popped_item = std::move(v_[head_]); + head_ = (head_ + 1) % max_items_; + } + + bool empty() + { + return tail_ == head_; + } + + bool full() + { + // head is ahead of the tail by 1 + return ((tail_ + 1) % max_items_) == head_; + } + + size_t overrun_counter() const + { + return overrun_counter_; + } + +private: + size_t max_items_; + typename std::vector::size_type head_ = 0; + typename std::vector::size_type tail_ = 0; + + std::vector v_; + + size_t overrun_counter_ = 0; +}; +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/console_globals.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/console_globals.h new file mode 100644 index 0000000..e2afb6b --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/console_globals.h @@ -0,0 +1,74 @@ +#pragma once +// +// Copyright(c) 2018 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#include "spdlog/details/null_mutex.h" +#include +#include + +#ifdef _WIN32 + +#ifndef NOMINMAX +#define NOMINMAX // prevent windows redefining min/max +#endif + +#ifndef WIN32_LEAN_AND_MEAN +#define WIN32_LEAN_AND_MEAN +#endif + +#include +#endif + +namespace spdlog { +namespace details { +struct console_stdout +{ + static std::FILE *stream() + { + return stdout; + } +#ifdef _WIN32 + static HANDLE handle() + { + return ::GetStdHandle(STD_OUTPUT_HANDLE); + } +#endif +}; + +struct console_stderr +{ + static std::FILE *stream() + { + return stderr; + } +#ifdef _WIN32 + static HANDLE handle() + { + return ::GetStdHandle(STD_ERROR_HANDLE); + } +#endif +}; + +struct console_mutex +{ + using mutex_t = std::mutex; + static mutex_t &mutex() + { + static mutex_t s_mutex; + return s_mutex; + } +}; + +struct console_nullmutex +{ + using mutex_t = null_mutex; + static mutex_t &mutex() + { + static mutex_t s_mutex; + return s_mutex; + } +}; +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/file_helper.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/file_helper.h new file mode 100644 index 0000000..8c1132d --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/file_helper.h @@ -0,0 +1,152 @@ +// +// Copyright(c) 2015 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +// Helper class for file sinks. +// When failing to open a file, retry several times(5) with a delay interval(10 ms). +// Throw spdlog_ex exception on errors. + +#include "spdlog/details/log_msg.h" +#include "spdlog/details/os.h" + +#include +#include +#include +#include +#include +#include + +namespace spdlog { +namespace details { + +class file_helper +{ + +public: + const int open_tries = 5; + const int open_interval = 10; + + explicit file_helper() = default; + + file_helper(const file_helper &) = delete; + file_helper &operator=(const file_helper &) = delete; + + ~file_helper() + { + close(); + } + + void open(const filename_t &fname, bool truncate = false) + { + close(); + auto *mode = truncate ? SPDLOG_FILENAME_T("wb") : SPDLOG_FILENAME_T("ab"); + _filename = fname; + for (int tries = 0; tries < open_tries; ++tries) + { + if (!os::fopen_s(&fd_, fname, mode)) + { + return; + } + + details::os::sleep_for_millis(open_interval); + } + + throw spdlog_ex("Failed opening file " + os::filename_to_str(_filename) + " for writing", errno); + } + + void reopen(bool truncate) + { + if (_filename.empty()) + { + throw spdlog_ex("Failed re opening file - was not opened before"); + } + open(_filename, truncate); + } + + void flush() + { + std::fflush(fd_); + } + + void close() + { + if (fd_ != nullptr) + { + std::fclose(fd_); + fd_ = nullptr; + } + } + + void write(const fmt::memory_buffer &buf) + { + size_t msg_size = buf.size(); + auto data = buf.data(); + if (std::fwrite(data, 1, msg_size, fd_) != msg_size) + { + throw spdlog_ex("Failed writing to file " + os::filename_to_str(_filename), errno); + } + } + + size_t size() const + { + if (fd_ == nullptr) + { + throw spdlog_ex("Cannot use size() on closed file " + os::filename_to_str(_filename)); + } + return os::filesize(fd_); + } + + const filename_t &filename() const + { + return _filename; + } + + static bool file_exists(const filename_t &fname) + { + return os::file_exists(fname); + } + + // + // return file path and its extension: + // + // "mylog.txt" => ("mylog", ".txt") + // "mylog" => ("mylog", "") + // "mylog." => ("mylog.", "") + // "/dir1/dir2/mylog.txt" => ("/dir1/dir2/mylog", ".txt") + // + // the starting dot in filenames is ignored (hidden files): + // + // ".mylog" => (".mylog". "") + // "my_folder/.mylog" => ("my_folder/.mylog", "") + // "my_folder/.mylog.txt" => ("my_folder/.mylog", ".txt") + static std::tuple split_by_extension(const spdlog::filename_t &fname) + { + auto ext_index = fname.rfind('.'); + + // no valid extension found - return whole path and empty string as + // extension + if (ext_index == filename_t::npos || ext_index == 0 || ext_index == fname.size() - 1) + { + return std::make_tuple(fname, spdlog::filename_t()); + } + + // treat casese like "/etc/rc.d/somelogfile or "/abc/.hiddenfile" + auto folder_index = fname.rfind(details::os::folder_sep); + if (folder_index != filename_t::npos && folder_index >= ext_index - 1) + { + return std::make_tuple(fname, spdlog::filename_t()); + } + + // finally - return a valid base and extension tuple + return std::make_tuple(fname.substr(0, ext_index), fname.substr(ext_index)); + } + +private: + std::FILE *fd_{nullptr}; + filename_t _filename; +}; +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/fmt_helper.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/fmt_helper.h new file mode 100644 index 0000000..d76aac4 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/fmt_helper.h @@ -0,0 +1,122 @@ +// +// Created by gabi on 6/15/18. +// + +#pragma once + +#include +#include +#include "spdlog/fmt/fmt.h" + +// Some fmt helpers to efficiently format and pad ints and strings +namespace spdlog { +namespace details { +namespace fmt_helper { + +template +inline spdlog::string_view_t to_string_view(const fmt::basic_memory_buffer &buf) SPDLOG_NOEXCEPT +{ + return spdlog::string_view_t(buf.data(), buf.size()); +} + +template +inline void append_buf(const fmt::basic_memory_buffer &buf, fmt::basic_memory_buffer &dest) +{ + auto *buf_ptr = buf.data(); + dest.append(buf_ptr, buf_ptr + buf.size()); +} + +template +inline void append_string_view(spdlog::string_view_t view, fmt::basic_memory_buffer &dest) +{ + auto *buf_ptr = view.data(); + if (buf_ptr != nullptr) + { + dest.append(buf_ptr, buf_ptr + view.size()); + } +} + +template +inline void append_int(T n, fmt::basic_memory_buffer &dest) +{ + fmt::format_int i(n); + dest.append(i.data(), i.data() + i.size()); +} + +template +inline unsigned count_digits(T n) +{ + using count_type = typename std::conditional<(sizeof(T) > sizeof(uint32_t)), uint64_t, uint32_t>::type; + return static_cast(fmt::internal::count_digits(static_cast(n))); +} + +template +inline void pad2(int n, fmt::basic_memory_buffer &dest) +{ + if (n > 99) + { + append_int(n, dest); + } + else if (n > 9) // 10-99 + { + dest.push_back(static_cast('0' + n / 10)); + dest.push_back(static_cast('0' + n % 10)); + } + else if (n >= 0) // 0-9 + { + dest.push_back('0'); + dest.push_back(static_cast('0' + n)); + } + else // negatives (unlikely, but just in case, let fmt deal with it) + { + fmt::format_to(dest, "{:02}", n); + } +} + +template +inline void pad_uint(T n, unsigned int width, fmt::basic_memory_buffer &dest) +{ + static_assert(std::is_unsigned::value, "pad_uint must get unsigned T"); + auto digits = count_digits(n); + if (width > digits) + { + const char *zeroes = "0000000000000000000"; + dest.append(zeroes, zeroes + width - digits); + } + append_int(n, dest); +} + +template +inline void pad3(T n, fmt::basic_memory_buffer &dest) +{ + pad_uint(n, 3, dest); +} + +template +inline void pad6(T n, fmt::basic_memory_buffer &dest) +{ + pad_uint(n, 6, dest); +} + +template +inline void pad9(T n, fmt::basic_memory_buffer &dest) +{ + pad_uint(n, 9, dest); +} + +// return fraction of a second of the given time_point. +// e.g. +// fraction(tp) -> will return the millis part of the second +template +inline ToDuration time_fraction(const log_clock::time_point &tp) +{ + using std::chrono::duration_cast; + using std::chrono::seconds; + auto duration = tp.time_since_epoch(); + auto secs = duration_cast(duration); + return duration_cast(duration) - duration_cast(secs); +} + +} // namespace fmt_helper +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/log_msg.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/log_msg.h new file mode 100644 index 0000000..69422ba --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/log_msg.h @@ -0,0 +1,55 @@ +// +// Copyright(c) 2015 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +#include "spdlog/common.h" +#include "spdlog/details/os.h" + +#include +#include + +namespace spdlog { +namespace details { +struct log_msg +{ + + log_msg(source_loc loc, const std::string *loggers_name, level::level_enum lvl, string_view_t view) + : logger_name(loggers_name) + , level(lvl) +#ifndef SPDLOG_NO_DATETIME + , time(os::now()) +#endif + +#ifndef SPDLOG_NO_THREAD_ID + , thread_id(os::thread_id()) +#endif + , source(loc) + , payload(view) + { + } + + log_msg(const std::string *loggers_name, level::level_enum lvl, string_view_t view) + : log_msg(source_loc{}, loggers_name, lvl, view) + { + } + + log_msg(const log_msg &other) = default; + + const std::string *logger_name{nullptr}; + level::level_enum level{level::off}; + log_clock::time_point time; + size_t thread_id{0}; + size_t msg_id{0}; + + // wrapping the formatted text with color (updated by pattern_formatter). + mutable size_t color_range_start{0}; + mutable size_t color_range_end{0}; + + source_loc source; + const string_view_t payload; +}; +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/logger_impl.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/logger_impl.h new file mode 100644 index 0000000..d44652b --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/logger_impl.h @@ -0,0 +1,435 @@ +// +// Copyright(c) 2015 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +#include "spdlog/details/fmt_helper.h" + +#include +#include + +#define SPDLOG_CATCH_AND_HANDLE \ + catch (const std::exception &ex) \ + { \ + err_handler_(ex.what()); \ + } \ + catch (...) \ + { \ + err_handler_("Unknown exception in logger"); \ + } + +// create logger with given name, sinks and the default pattern formatter +// all other ctors will call this one +template +inline spdlog::logger::logger(std::string logger_name, It begin, It end) + : name_(std::move(logger_name)) + , sinks_(begin, end) +{ +} + +// ctor with sinks as init list +inline spdlog::logger::logger(std::string logger_name, sinks_init_list sinks_list) + : logger(std::move(logger_name), sinks_list.begin(), sinks_list.end()) +{ +} + +// ctor with single sink +inline spdlog::logger::logger(std::string logger_name, spdlog::sink_ptr single_sink) + : logger(std::move(logger_name), {std::move(single_sink)}) +{ +} + +inline spdlog::logger::~logger() = default; + +inline void spdlog::logger::set_formatter(std::unique_ptr f) +{ + for (auto &sink : sinks_) + { + sink->set_formatter(f->clone()); + } +} + +inline void spdlog::logger::set_pattern(std::string pattern, pattern_time_type time_type) +{ + auto new_formatter = details::make_unique(std::move(pattern), time_type); + set_formatter(std::move(new_formatter)); +} + +template +inline void spdlog::logger::log(source_loc source, level::level_enum lvl, const char *fmt, const Args &... args) +{ + if (!should_log(lvl)) + { + return; + } + + try + { + using details::fmt_helper::to_string_view; + fmt::memory_buffer buf; + fmt::format_to(buf, fmt, args...); + details::log_msg log_msg(source, &name_, lvl, to_string_view(buf)); + sink_it_(log_msg); + } + SPDLOG_CATCH_AND_HANDLE +} + +template +inline void spdlog::logger::log(level::level_enum lvl, const char *fmt, const Args &... args) +{ + log(source_loc{}, lvl, fmt, args...); +} + +inline void spdlog::logger::log(source_loc source, level::level_enum lvl, const char *msg) +{ + if (!should_log(lvl)) + { + return; + } + + try + { + details::log_msg log_msg(source, &name_, lvl, spdlog::string_view_t(msg)); + sink_it_(log_msg); + } + SPDLOG_CATCH_AND_HANDLE +} + +inline void spdlog::logger::log(level::level_enum lvl, const char *msg) +{ + log(source_loc{}, lvl, msg); +} + +template +inline void spdlog::logger::log(level::level_enum lvl, const T &msg) +{ + log(source_loc{}, lvl, msg); +} + +template::value, T>::type *> +inline void spdlog::logger::log(source_loc source, level::level_enum lvl, const T &msg) +{ + if (!should_log(lvl)) + { + return; + } + try + { + details::log_msg log_msg(source, &name_, lvl, msg); + sink_it_(log_msg); + } + SPDLOG_CATCH_AND_HANDLE +} + +template::value, T>::type *> +inline void spdlog::logger::log(source_loc source, level::level_enum lvl, const T &msg) +{ + if (!should_log(lvl)) + { + return; + } + try + { + using details::fmt_helper::to_string_view; + fmt::memory_buffer buf; + fmt::format_to(buf, "{}", msg); + details::log_msg log_msg(source, &name_, lvl, to_string_view(buf)); + sink_it_(log_msg); + } + SPDLOG_CATCH_AND_HANDLE +} + +template +inline void spdlog::logger::trace(const char *fmt, const Args &... args) +{ + log(level::trace, fmt, args...); +} + +template +inline void spdlog::logger::debug(const char *fmt, const Args &... args) +{ + log(level::debug, fmt, args...); +} + +template +inline void spdlog::logger::info(const char *fmt, const Args &... args) +{ + log(level::info, fmt, args...); +} + +template +inline void spdlog::logger::warn(const char *fmt, const Args &... args) +{ + log(level::warn, fmt, args...); +} + +template +inline void spdlog::logger::error(const char *fmt, const Args &... args) +{ + log(level::err, fmt, args...); +} + +template +inline void spdlog::logger::critical(const char *fmt, const Args &... args) +{ + log(level::critical, fmt, args...); +} + +template +inline void spdlog::logger::trace(const T &msg) +{ + log(level::trace, msg); +} + +template +inline void spdlog::logger::debug(const T &msg) +{ + log(level::debug, msg); +} + +template +inline void spdlog::logger::info(const T &msg) +{ + log(level::info, msg); +} + +template +inline void spdlog::logger::warn(const T &msg) +{ + log(level::warn, msg); +} + +template +inline void spdlog::logger::error(const T &msg) +{ + log(level::err, msg); +} + +template +inline void spdlog::logger::critical(const T &msg) +{ + log(level::critical, msg); +} + +#ifdef SPDLOG_WCHAR_TO_UTF8_SUPPORT + +inline void wbuf_to_utf8buf(const fmt::wmemory_buffer &wbuf, fmt::memory_buffer &target) +{ + int wbuf_size = static_cast(wbuf.size()); + if (wbuf_size == 0) + { + return; + } + + auto result_size = ::WideCharToMultiByte(CP_UTF8, 0, wbuf.data(), wbuf_size, NULL, 0, NULL, NULL); + + if (result_size > 0) + { + target.resize(result_size); + ::WideCharToMultiByte(CP_UTF8, 0, wbuf.data(), wbuf_size, &target.data()[0], result_size, NULL, NULL); + } + else + { + throw spdlog::spdlog_ex(fmt::format("WideCharToMultiByte failed. Last error: {}", ::GetLastError())); + } +} + +template +inline void spdlog::logger::log(source_loc source, level::level_enum lvl, const wchar_t *fmt, const Args &... args) +{ + if (!should_log(lvl)) + { + return; + } + + try + { + // format to wmemory_buffer and convert to utf8 + using details::fmt_helper::to_string_view; + fmt::wmemory_buffer wbuf; + fmt::format_to(wbuf, fmt, args...); + fmt::memory_buffer buf; + wbuf_to_utf8buf(wbuf, buf); + details::log_msg log_msg(source, &name_, lvl, to_string_view(buf)); + sink_it_(log_msg); + } + SPDLOG_CATCH_AND_HANDLE +} + +template +inline void spdlog::logger::log(level::level_enum lvl, const wchar_t *fmt, const Args &... args) +{ + log(source_loc{}, lvl, fmt, args...); +} + +template +inline void spdlog::logger::trace(const wchar_t *fmt, const Args &... args) +{ + log(level::trace, fmt, args...); +} + +template +inline void spdlog::logger::debug(const wchar_t *fmt, const Args &... args) +{ + log(level::debug, fmt, args...); +} + +template +inline void spdlog::logger::info(const wchar_t *fmt, const Args &... args) +{ + log(level::info, fmt, args...); +} + +template +inline void spdlog::logger::warn(const wchar_t *fmt, const Args &... args) +{ + log(level::warn, fmt, args...); +} + +template +inline void spdlog::logger::error(const wchar_t *fmt, const Args &... args) +{ + log(level::err, fmt, args...); +} + +template +inline void spdlog::logger::critical(const wchar_t *fmt, const Args &... args) +{ + log(level::critical, fmt, args...); +} + +#endif // SPDLOG_WCHAR_TO_UTF8_SUPPORT + +// +// name and level +// +inline const std::string &spdlog::logger::name() const +{ + return name_; +} + +inline void spdlog::logger::set_level(spdlog::level::level_enum log_level) +{ + level_.store(log_level); +} + +inline void spdlog::logger::set_error_handler(spdlog::log_err_handler err_handler) +{ + err_handler_ = std::move(err_handler); +} + +inline spdlog::log_err_handler spdlog::logger::error_handler() const +{ + return err_handler_; +} + +inline void spdlog::logger::flush() +{ + try + { + flush_(); + } + SPDLOG_CATCH_AND_HANDLE +} + +inline void spdlog::logger::flush_on(level::level_enum log_level) +{ + flush_level_.store(log_level); +} + +inline spdlog::level::level_enum spdlog::logger::flush_level() const +{ + return static_cast(flush_level_.load(std::memory_order_relaxed)); +} + +inline bool spdlog::logger::should_flush_(const details::log_msg &msg) +{ + auto flush_level = flush_level_.load(std::memory_order_relaxed); + return (msg.level >= flush_level) && (msg.level != level::off); +} + +inline spdlog::level::level_enum spdlog::logger::default_level() +{ + return static_cast(SPDLOG_ACTIVE_LEVEL); +} + +inline spdlog::level::level_enum spdlog::logger::level() const +{ + return static_cast(level_.load(std::memory_order_relaxed)); +} + +inline bool spdlog::logger::should_log(spdlog::level::level_enum msg_level) const +{ + return msg_level >= level_.load(std::memory_order_relaxed); +} + +// +// protected virtual called at end of each user log call (if enabled) by the +// line_logger +// +inline void spdlog::logger::sink_it_(details::log_msg &msg) +{ +#if defined(SPDLOG_ENABLE_MESSAGE_COUNTER) + incr_msg_counter_(msg); +#endif + for (auto &sink : sinks_) + { + if (sink->should_log(msg.level)) + { + sink->log(msg); + } + } + + if (should_flush_(msg)) + { + flush_(); + } +} + +inline void spdlog::logger::flush_() +{ + for (auto &sink : sinks_) + { + sink->flush(); + } +} + +inline void spdlog::logger::default_err_handler_(const std::string &msg) +{ + auto now = time(nullptr); + if (now - last_err_time_ < 60) + { + return; + } + last_err_time_ = now; + auto tm_time = details::os::localtime(now); + char date_buf[100]; + std::strftime(date_buf, sizeof(date_buf), "%Y-%m-%d %H:%M:%S", &tm_time); + fmt::print(stderr, "[*** LOG ERROR ***] [{}] [{}] {}\n", date_buf, name(), msg); +} + +inline void spdlog::logger::incr_msg_counter_(details::log_msg &msg) +{ + msg.msg_id = msg_counter_.fetch_add(1, std::memory_order_relaxed); +} + +inline const std::vector &spdlog::logger::sinks() const +{ + return sinks_; +} + +inline std::vector &spdlog::logger::sinks() +{ + return sinks_; +} + +inline std::shared_ptr spdlog::logger::clone(std::string logger_name) +{ + auto cloned = std::make_shared(std::move(logger_name), sinks_.begin(), sinks_.end()); + cloned->set_level(this->level()); + cloned->flush_on(this->flush_level()); + cloned->set_error_handler(this->error_handler()); + return cloned; +} diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/mpmc_blocking_q.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/mpmc_blocking_q.h new file mode 100644 index 0000000..ca789fc --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/mpmc_blocking_q.h @@ -0,0 +1,121 @@ +#pragma once + +// +// Copyright(c) 2018 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +// multi producer-multi consumer blocking queue. +// enqueue(..) - will block until room found to put the new message. +// enqueue_nowait(..) - will return immediately with false if no room left in +// the queue. +// dequeue_for(..) - will block until the queue is not empty or timeout have +// passed. + +#include "spdlog/details/circular_q.h" + +#include +#include + +namespace spdlog { +namespace details { + +template +class mpmc_blocking_queue +{ +public: + using item_type = T; + explicit mpmc_blocking_queue(size_t max_items) + : q_(max_items) + { + } + +#ifndef __MINGW32__ + // try to enqueue and block if no room left + void enqueue(T &&item) + { + { + std::unique_lock lock(queue_mutex_); + pop_cv_.wait(lock, [this] { return !this->q_.full(); }); + q_.push_back(std::move(item)); + } + push_cv_.notify_one(); + } + + // enqueue immediately. overrun oldest message in the queue if no room left. + void enqueue_nowait(T &&item) + { + { + std::unique_lock lock(queue_mutex_); + q_.push_back(std::move(item)); + } + push_cv_.notify_one(); + } + + // try to dequeue item. if no item found. wait upto timeout and try again + // Return true, if succeeded dequeue item, false otherwise + bool dequeue_for(T &popped_item, std::chrono::milliseconds wait_duration) + { + { + std::unique_lock lock(queue_mutex_); + if (!push_cv_.wait_for(lock, wait_duration, [this] { return !this->q_.empty(); })) + { + return false; + } + q_.pop_front(popped_item); + } + pop_cv_.notify_one(); + return true; + } + +#else + // apparently mingw deadlocks if the mutex is released before cv.notify_one(), + // so release the mutex at the very end each function. + + // try to enqueue and block if no room left + void enqueue(T &&item) + { + std::unique_lock lock(queue_mutex_); + pop_cv_.wait(lock, [this] { return !this->q_.full(); }); + q_.push_back(std::move(item)); + push_cv_.notify_one(); + } + + // enqueue immediately. overrun oldest message in the queue if no room left. + void enqueue_nowait(T &&item) + { + std::unique_lock lock(queue_mutex_); + q_.push_back(std::move(item)); + push_cv_.notify_one(); + } + + // try to dequeue item. if no item found. wait upto timeout and try again + // Return true, if succeeded dequeue item, false otherwise + bool dequeue_for(T &popped_item, std::chrono::milliseconds wait_duration) + { + std::unique_lock lock(queue_mutex_); + if (!push_cv_.wait_for(lock, wait_duration, [this] { return !this->q_.empty(); })) + { + return false; + } + q_.pop_front(popped_item); + pop_cv_.notify_one(); + return true; + } + +#endif + + size_t overrun_counter() + { + std::unique_lock lock(queue_mutex_); + return q_.overrun_counter(); + } + +private: + std::mutex queue_mutex_; + std::condition_variable push_cv_; + std::condition_variable pop_cv_; + spdlog::details::circular_q q_; +}; +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/null_mutex.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/null_mutex.h new file mode 100644 index 0000000..3f495bd --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/null_mutex.h @@ -0,0 +1,45 @@ +// +// Copyright(c) 2015 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +#include +// null, no cost dummy "mutex" and dummy "atomic" int + +namespace spdlog { +namespace details { +struct null_mutex +{ + void lock() {} + void unlock() {} + bool try_lock() + { + return true; + } +}; + +struct null_atomic_int +{ + int value; + null_atomic_int() = default; + + explicit null_atomic_int(int val) + : value(val) + { + } + + int load(std::memory_order) const + { + return value; + } + + void store(int val) + { + value = val; + } +}; + +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/os.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/os.h new file mode 100644 index 0000000..646805e --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/os.h @@ -0,0 +1,421 @@ +// +// Copyright(c) 2015 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// +#pragma once + +#include "../common.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef _WIN32 + +#ifndef NOMINMAX +#define NOMINMAX // prevent windows redefining min/max +#endif + +#ifndef WIN32_LEAN_AND_MEAN +#define WIN32_LEAN_AND_MEAN +#endif +#include // _get_osfhandle and _isatty support +#include // _get_pid support +#include + +#ifdef __MINGW32__ +#include +#endif + +#else // unix + +#include +#include + +#ifdef __linux__ +#include //Use gettid() syscall under linux to get thread id + +#elif __FreeBSD__ +#include //Use thr_self() syscall under FreeBSD to get thread id +#endif + +#endif // unix + +#ifndef __has_feature // Clang - feature checking macros. +#define __has_feature(x) 0 // Compatibility with non-clang compilers. +#endif + +namespace spdlog { +namespace details { +namespace os { + +inline spdlog::log_clock::time_point now() SPDLOG_NOEXCEPT +{ + +#if defined __linux__ && defined SPDLOG_CLOCK_COARSE + timespec ts; + ::clock_gettime(CLOCK_REALTIME_COARSE, &ts); + return std::chrono::time_point( + std::chrono::duration_cast(std::chrono::seconds(ts.tv_sec) + std::chrono::nanoseconds(ts.tv_nsec))); + +#else + return log_clock::now(); +#endif +} +inline std::tm localtime(const std::time_t &time_tt) SPDLOG_NOEXCEPT +{ + +#ifdef _WIN32 + std::tm tm; + localtime_s(&tm, &time_tt); +#else + std::tm tm; + localtime_r(&time_tt, &tm); +#endif + return tm; +} + +inline std::tm localtime() SPDLOG_NOEXCEPT +{ + std::time_t now_t = time(nullptr); + return localtime(now_t); +} + +inline std::tm gmtime(const std::time_t &time_tt) SPDLOG_NOEXCEPT +{ + +#ifdef _WIN32 + std::tm tm; + gmtime_s(&tm, &time_tt); +#else + std::tm tm; + gmtime_r(&time_tt, &tm); +#endif + return tm; +} + +inline std::tm gmtime() SPDLOG_NOEXCEPT +{ + std::time_t now_t = time(nullptr); + return gmtime(now_t); +} + +// eol definition +#if !defined(SPDLOG_EOL) +#ifdef _WIN32 +#define SPDLOG_EOL "\r\n" +#else +#define SPDLOG_EOL "\n" +#endif +#endif + +SPDLOG_CONSTEXPR static const char *default_eol = SPDLOG_EOL; + +// folder separator +#ifdef _WIN32 +SPDLOG_CONSTEXPR static const char folder_sep = '\\'; +#else +SPDLOG_CONSTEXPR static const char folder_sep = '/'; +#endif + +inline void prevent_child_fd(FILE *f) +{ + +#ifdef _WIN32 +#if !defined(__cplusplus_winrt) + auto file_handle = (HANDLE)_get_osfhandle(_fileno(f)); + if (!::SetHandleInformation(file_handle, HANDLE_FLAG_INHERIT, 0)) + throw spdlog_ex("SetHandleInformation failed", errno); +#endif +#else + auto fd = fileno(f); + if (fcntl(fd, F_SETFD, FD_CLOEXEC) == -1) + { + throw spdlog_ex("fcntl with FD_CLOEXEC failed", errno); + } +#endif +} + +// fopen_s on non windows for writing +inline bool fopen_s(FILE **fp, const filename_t &filename, const filename_t &mode) +{ +#ifdef _WIN32 +#ifdef SPDLOG_WCHAR_FILENAMES + *fp = _wfsopen((filename.c_str()), mode.c_str(), _SH_DENYNO); +#else + *fp = _fsopen((filename.c_str()), mode.c_str(), _SH_DENYNO); +#endif +#else // unix + *fp = fopen((filename.c_str()), mode.c_str()); +#endif + +#ifdef SPDLOG_PREVENT_CHILD_FD + if (*fp != nullptr) + { + prevent_child_fd(*fp); + } +#endif + return *fp == nullptr; +} + +inline int remove(const filename_t &filename) SPDLOG_NOEXCEPT +{ +#if defined(_WIN32) && defined(SPDLOG_WCHAR_FILENAMES) + return _wremove(filename.c_str()); +#else + return std::remove(filename.c_str()); +#endif +} + +inline int rename(const filename_t &filename1, const filename_t &filename2) SPDLOG_NOEXCEPT +{ +#if defined(_WIN32) && defined(SPDLOG_WCHAR_FILENAMES) + return _wrename(filename1.c_str(), filename2.c_str()); +#else + return std::rename(filename1.c_str(), filename2.c_str()); +#endif +} + +// Return if file exists +inline bool file_exists(const filename_t &filename) SPDLOG_NOEXCEPT +{ +#ifdef _WIN32 +#ifdef SPDLOG_WCHAR_FILENAMES + auto attribs = GetFileAttributesW(filename.c_str()); +#else + auto attribs = GetFileAttributesA(filename.c_str()); +#endif + return (attribs != INVALID_FILE_ATTRIBUTES && !(attribs & FILE_ATTRIBUTE_DIRECTORY)); +#else // common linux/unix all have the stat system call + struct stat buffer; + return (stat(filename.c_str(), &buffer) == 0); +#endif +} + +// Return file size according to open FILE* object +inline size_t filesize(FILE *f) +{ + if (f == nullptr) + { + throw spdlog_ex("Failed getting file size. fd is null"); + } +#if defined(_WIN32) && !defined(__CYGWIN__) + int fd = _fileno(f); +#if _WIN64 // 64 bits + __int64 ret = _filelengthi64(fd); + if (ret >= 0) + { + return static_cast(ret); + } + +#else // windows 32 bits + long ret = _filelength(fd); + if (ret >= 0) + { + return static_cast(ret); + } +#endif + +#else // unix + int fd = fileno(f); +// 64 bits(but not in osx or cygwin, where fstat64 is deprecated) +#if !defined(__FreeBSD__) && !defined(__APPLE__) && (defined(__x86_64__) || defined(__ppc64__)) && !defined(__CYGWIN__) + struct stat64 st; + if (fstat64(fd, &st) == 0) + { + return static_cast(st.st_size); + } +#else // unix 32 bits or cygwin + struct stat st; + + if (fstat(fd, &st) == 0) + { + return static_cast(st.st_size); + } +#endif +#endif + throw spdlog_ex("Failed getting file size from fd", errno); +} + +// Return utc offset in minutes or throw spdlog_ex on failure +inline int utc_minutes_offset(const std::tm &tm = details::os::localtime()) +{ + +#ifdef _WIN32 +#if _WIN32_WINNT < _WIN32_WINNT_WS08 + TIME_ZONE_INFORMATION tzinfo; + auto rv = GetTimeZoneInformation(&tzinfo); +#else + DYNAMIC_TIME_ZONE_INFORMATION tzinfo; + auto rv = GetDynamicTimeZoneInformation(&tzinfo); +#endif + if (rv == TIME_ZONE_ID_INVALID) + throw spdlog::spdlog_ex("Failed getting timezone info. ", errno); + + int offset = -tzinfo.Bias; + if (tm.tm_isdst) + { + offset -= tzinfo.DaylightBias; + } + else + { + offset -= tzinfo.StandardBias; + } + return offset; +#else + +#if defined(sun) || defined(__sun) || defined(_AIX) + // 'tm_gmtoff' field is BSD extension and it's missing on SunOS/Solaris + struct helper + { + static long int calculate_gmt_offset(const std::tm &localtm = details::os::localtime(), const std::tm &gmtm = details::os::gmtime()) + { + int local_year = localtm.tm_year + (1900 - 1); + int gmt_year = gmtm.tm_year + (1900 - 1); + + long int days = ( + // difference in day of year + localtm.tm_yday - + gmtm.tm_yday + + // + intervening leap days + + ((local_year >> 2) - (gmt_year >> 2)) - (local_year / 100 - gmt_year / 100) + + ((local_year / 100 >> 2) - (gmt_year / 100 >> 2)) + + // + difference in years * 365 */ + + (long int)(local_year - gmt_year) * 365); + + long int hours = (24 * days) + (localtm.tm_hour - gmtm.tm_hour); + long int mins = (60 * hours) + (localtm.tm_min - gmtm.tm_min); + long int secs = (60 * mins) + (localtm.tm_sec - gmtm.tm_sec); + + return secs; + } + }; + + auto offset_seconds = helper::calculate_gmt_offset(tm); +#else + auto offset_seconds = tm.tm_gmtoff; +#endif + + return static_cast(offset_seconds / 60); +#endif +} + +// Return current thread id as size_t +// It exists because the std::this_thread::get_id() is much slower(especially +// under VS 2013) +inline size_t _thread_id() SPDLOG_NOEXCEPT +{ +#ifdef _WIN32 + return static_cast(::GetCurrentThreadId()); +#elif __linux__ +#if defined(__ANDROID__) && defined(__ANDROID_API__) && (__ANDROID_API__ < 21) +#define SYS_gettid __NR_gettid +#endif + return static_cast(syscall(SYS_gettid)); +#elif __FreeBSD__ + long tid; + thr_self(&tid); + return static_cast(tid); +#elif __APPLE__ + uint64_t tid; + pthread_threadid_np(nullptr, &tid); + return static_cast(tid); +#else // Default to standard C++11 (other Unix) + return static_cast(std::hash()(std::this_thread::get_id())); +#endif +} + +// Return current thread id as size_t (from thread local storage) +inline size_t thread_id() SPDLOG_NOEXCEPT +{ +#if defined(SPDLOG_NO_TLS) + return _thread_id(); +#else // cache thread id in tls + static thread_local const size_t tid = _thread_id(); + return tid; +#endif +} + +// This is avoid msvc issue in sleep_for that happens if the clock changes. +// See https://github.com/gabime/spdlog/issues/609 +inline void sleep_for_millis(int milliseconds) SPDLOG_NOEXCEPT +{ +#if defined(_WIN32) + ::Sleep(milliseconds); +#else + std::this_thread::sleep_for(std::chrono::milliseconds(milliseconds)); +#endif +} + +// wchar support for windows file names (SPDLOG_WCHAR_FILENAMES must be defined) +#if defined(_WIN32) && defined(SPDLOG_WCHAR_FILENAMES) +#define SPDLOG_FILENAME_T(s) L##s +inline std::string filename_to_str(const filename_t &filename) +{ + std::wstring_convert, wchar_t> c; + return c.to_bytes(filename); +} +#else +#define SPDLOG_FILENAME_T(s) s +inline std::string filename_to_str(const filename_t &filename) +{ + return filename; +} +#endif + +inline int pid() +{ + +#ifdef _WIN32 + return static_cast(::GetCurrentProcessId()); +#else + return static_cast(::getpid()); +#endif +} + +// Determine if the terminal supports colors +// Source: https://github.com/agauniyal/rang/ +inline bool is_color_terminal() SPDLOG_NOEXCEPT +{ +#ifdef _WIN32 + return true; +#else + static constexpr const char *Terms[] = { + "ansi", "color", "console", "cygwin", "gnome", "konsole", "kterm", "linux", "msys", "putty", "rxvt", "screen", "vt100", "xterm"}; + + const char *env_p = std::getenv("TERM"); + if (env_p == nullptr) + { + return false; + } + + static const bool result = + std::any_of(std::begin(Terms), std::end(Terms), [&](const char *term) { return std::strstr(env_p, term) != nullptr; }); + return result; +#endif +} + +// Detrmine if the terminal attached +// Source: https://github.com/agauniyal/rang/ +inline bool in_terminal(FILE *file) SPDLOG_NOEXCEPT +{ + +#ifdef _WIN32 + return _isatty(_fileno(file)) != 0; +#else + return isatty(fileno(file)) != 0; +#endif +} +} // namespace os +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/pattern_formatter.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/pattern_formatter.h new file mode 100644 index 0000000..c0ad86e --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/pattern_formatter.h @@ -0,0 +1,1336 @@ +// +// Copyright(c) 2015 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +#include "spdlog/details/fmt_helper.h" +#include "spdlog/details/log_msg.h" +#include "spdlog/details/os.h" +#include "spdlog/fmt/fmt.h" +#include "spdlog/formatter.h" + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +namespace spdlog { +namespace details { + +// padding information. +struct padding_info +{ + enum pad_side + { + left, + right, + center + }; + + padding_info() = default; + padding_info(size_t width, padding_info::pad_side side) + : width_(width) + , side_(side) + { + } + + bool enabled() const + { + return width_ != 0; + } + const size_t width_ = 0; + const pad_side side_ = left; +}; + +class scoped_pad +{ +public: + scoped_pad(size_t wrapped_size, padding_info &padinfo, fmt::memory_buffer &dest) + : padinfo_(padinfo) + , dest_(dest) + { + + if (padinfo_.width_ <= wrapped_size) + { + total_pad_ = 0; + return; + } + + total_pad_ = padinfo.width_ - wrapped_size; + if (padinfo_.side_ == padding_info::left) + { + pad_it(total_pad_); + total_pad_ = 0; + } + else if (padinfo_.side_ == padding_info::center) + { + auto half_pad = total_pad_ / 2; + auto reminder = total_pad_ & 1; + pad_it(half_pad); + total_pad_ = half_pad + reminder; // for the right side + } + } + + scoped_pad(spdlog::string_view_t txt, padding_info &padinfo, fmt::memory_buffer &dest) + : scoped_pad(txt.size(), padinfo, dest) + { + } + + ~scoped_pad() + { + if (total_pad_) + { + pad_it(total_pad_); + } + } + +private: + void pad_it(size_t count) + { + // count = std::min(count, spaces_.size()); + assert(count <= spaces_.size()); + fmt_helper::append_string_view(string_view_t(spaces_.data(), count), dest_); + } + + const padding_info &padinfo_; + fmt::memory_buffer &dest_; + size_t total_pad_; + string_view_t spaces_{" " + " ", + 128}; +}; + +class flag_formatter +{ +public: + explicit flag_formatter(padding_info padinfo) + : padinfo_(padinfo) + { + } + flag_formatter() = default; + virtual ~flag_formatter() = default; + virtual void format(const details::log_msg &msg, const std::tm &tm_time, fmt::memory_buffer &dest) = 0; + +protected: + padding_info padinfo_; +}; + +/////////////////////////////////////////////////////////////////////// +// name & level pattern appender +/////////////////////////////////////////////////////////////////////// +class name_formatter : public flag_formatter +{ +public: + explicit name_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + if (padinfo_.enabled()) + { + scoped_pad p(*msg.logger_name, padinfo_, dest); + fmt_helper::append_string_view(*msg.logger_name, dest); + } + else + { + fmt_helper::append_string_view(*msg.logger_name, dest); + } + } +}; + +// log level appender +class level_formatter : public flag_formatter +{ +public: + explicit level_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + string_view_t &level_name = level::to_string_view(msg.level); + if (padinfo_.enabled()) + { + scoped_pad p(level_name, padinfo_, dest); + fmt_helper::append_string_view(level_name, dest); + } + else + { + fmt_helper::append_string_view(level_name, dest); + } + } +}; + +// short log level appender +class short_level_formatter : public flag_formatter +{ +public: + explicit short_level_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + string_view_t level_name{level::to_short_c_str(msg.level)}; + scoped_pad p(level_name, padinfo_, dest); + fmt_helper::append_string_view(level_name, dest); + } +}; + +/////////////////////////////////////////////////////////////////////// +// Date time pattern appenders +/////////////////////////////////////////////////////////////////////// + +static const char *ampm(const tm &t) +{ + return t.tm_hour >= 12 ? "PM" : "AM"; +} + +static int to12h(const tm &t) +{ + return t.tm_hour > 12 ? t.tm_hour - 12 : t.tm_hour; +} + +// Abbreviated weekday name +static const char *days[]{"Sun", "Mon", "Tue", "Wed", "Thu", "Fri", "Sat"}; +class a_formatter : public flag_formatter +{ +public: + explicit a_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + string_view_t field_value{days[tm_time.tm_wday]}; + scoped_pad p(field_value, padinfo_, dest); + fmt_helper::append_string_view(field_value, dest); + } +}; + +// Full weekday name +static const char *full_days[]{"Sunday", "Monday", "Tuesday", "Wednesday", "Thursday", "Friday", "Saturday"}; +class A_formatter : public flag_formatter +{ +public: + explicit A_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + string_view_t field_value{full_days[tm_time.tm_wday]}; + scoped_pad p(field_value, padinfo_, dest); + fmt_helper::append_string_view(field_value, dest); + } +}; + +// Abbreviated month +static const char *months[]{"Jan", "Feb", "Mar", "Apr", "May", "Jun", "Jul", "Aug", "Sept", "Oct", "Nov", "Dec"}; +class b_formatter : public flag_formatter +{ +public: + explicit b_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + string_view_t field_value{months[tm_time.tm_mon]}; + scoped_pad p(field_value, padinfo_, dest); + fmt_helper::append_string_view(field_value, dest); + } +}; + +// Full month name +static const char *full_months[]{ + "January", "February", "March", "April", "May", "June", "July", "August", "September", "October", "November", "December"}; +class B_formatter : public flag_formatter +{ +public: + explicit B_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + string_view_t field_value{full_months[tm_time.tm_mon]}; + scoped_pad p(field_value, padinfo_, dest); + fmt_helper::append_string_view(field_value, dest); + } +}; + +// Date and time representation (Thu Aug 23 15:35:46 2014) +class c_formatter final : public flag_formatter +{ +public: + explicit c_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 24; + scoped_pad p(field_size, padinfo_, dest); + + fmt_helper::append_string_view(days[tm_time.tm_wday], dest); + dest.push_back(' '); + fmt_helper::append_string_view(months[tm_time.tm_mon], dest); + dest.push_back(' '); + fmt_helper::append_int(tm_time.tm_mday, dest); + dest.push_back(' '); + // time + + fmt_helper::pad2(tm_time.tm_hour, dest); + dest.push_back(':'); + fmt_helper::pad2(tm_time.tm_min, dest); + dest.push_back(':'); + fmt_helper::pad2(tm_time.tm_sec, dest); + dest.push_back(' '); + fmt_helper::append_int(tm_time.tm_year + 1900, dest); + } +}; + +// year - 2 digit +class C_formatter final : public flag_formatter +{ +public: + explicit C_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 2; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::pad2(tm_time.tm_year % 100, dest); + } +}; + +// Short MM/DD/YY date, equivalent to %m/%d/%y 08/23/01 +class D_formatter final : public flag_formatter +{ +public: + explicit D_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 10; + scoped_pad p(field_size, padinfo_, dest); + + fmt_helper::pad2(tm_time.tm_mon + 1, dest); + dest.push_back('/'); + fmt_helper::pad2(tm_time.tm_mday, dest); + dest.push_back('/'); + fmt_helper::pad2(tm_time.tm_year % 100, dest); + } +}; + +// year - 4 digit +class Y_formatter final : public flag_formatter +{ +public: + explicit Y_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 4; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::append_int(tm_time.tm_year + 1900, dest); + } +}; + +// month 1-12 +class m_formatter final : public flag_formatter +{ +public: + explicit m_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 2; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::pad2(tm_time.tm_mon + 1, dest); + } +}; + +// day of month 1-31 +class d_formatter final : public flag_formatter +{ +public: + explicit d_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 2; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::pad2(tm_time.tm_mday, dest); + } +}; + +// hours in 24 format 0-23 +class H_formatter final : public flag_formatter +{ +public: + explicit H_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 2; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::pad2(tm_time.tm_hour, dest); + } +}; + +// hours in 12 format 1-12 +class I_formatter final : public flag_formatter +{ +public: + explicit I_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 2; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::pad2(to12h(tm_time), dest); + } +}; + +// minutes 0-59 +class M_formatter final : public flag_formatter +{ +public: + explicit M_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 2; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::pad2(tm_time.tm_min, dest); + } +}; + +// seconds 0-59 +class S_formatter final : public flag_formatter +{ +public: + explicit S_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 2; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::pad2(tm_time.tm_sec, dest); + } +}; + +// milliseconds +class e_formatter final : public flag_formatter +{ +public: + explicit e_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + auto millis = fmt_helper::time_fraction(msg.time); + if (padinfo_.enabled()) + { + const size_t field_size = 3; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::pad3(static_cast(millis.count()), dest); + } + else + { + fmt_helper::pad3(static_cast(millis.count()), dest); + } + } +}; + +// microseconds +class f_formatter final : public flag_formatter +{ +public: + explicit f_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + auto micros = fmt_helper::time_fraction(msg.time); + if (padinfo_.enabled()) + { + const size_t field_size = 6; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::pad6(static_cast(micros.count()), dest); + } + else + { + fmt_helper::pad6(static_cast(micros.count()), dest); + } + } +}; + +// nanoseconds +class F_formatter final : public flag_formatter +{ +public: + explicit F_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + auto ns = fmt_helper::time_fraction(msg.time); + if (padinfo_.enabled()) + { + const size_t field_size = 9; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::pad9(static_cast(ns.count()), dest); + } + else + { + fmt_helper::pad9(static_cast(ns.count()), dest); + } + } +}; + +// seconds since epoch +class E_formatter final : public flag_formatter +{ +public: + explicit E_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + const size_t field_size = 10; + scoped_pad p(field_size, padinfo_, dest); + auto duration = msg.time.time_since_epoch(); + auto seconds = std::chrono::duration_cast(duration).count(); + fmt_helper::append_int(seconds, dest); + } +}; + +// AM/PM +class p_formatter final : public flag_formatter +{ +public: + explicit p_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 2; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::append_string_view(ampm(tm_time), dest); + } +}; + +// 12 hour clock 02:55:02 pm +class r_formatter final : public flag_formatter +{ +public: + explicit r_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 11; + scoped_pad p(field_size, padinfo_, dest); + + fmt_helper::pad2(to12h(tm_time), dest); + dest.push_back(':'); + fmt_helper::pad2(tm_time.tm_min, dest); + dest.push_back(':'); + fmt_helper::pad2(tm_time.tm_sec, dest); + dest.push_back(' '); + fmt_helper::append_string_view(ampm(tm_time), dest); + } +}; + +// 24-hour HH:MM time, equivalent to %H:%M +class R_formatter final : public flag_formatter +{ +public: + explicit R_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 5; + scoped_pad p(field_size, padinfo_, dest); + + fmt_helper::pad2(tm_time.tm_hour, dest); + dest.push_back(':'); + fmt_helper::pad2(tm_time.tm_min, dest); + } +}; + +// ISO 8601 time format (HH:MM:SS), equivalent to %H:%M:%S +class T_formatter final : public flag_formatter +{ +public: + explicit T_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 8; + scoped_pad p(field_size, padinfo_, dest); + + fmt_helper::pad2(tm_time.tm_hour, dest); + dest.push_back(':'); + fmt_helper::pad2(tm_time.tm_min, dest); + dest.push_back(':'); + fmt_helper::pad2(tm_time.tm_sec, dest); + } +}; + +// ISO 8601 offset from UTC in timezone (+-HH:MM) +class z_formatter final : public flag_formatter +{ +public: + explicit z_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + const std::chrono::seconds cache_refresh = std::chrono::seconds(5); + + z_formatter() = default; + z_formatter(const z_formatter &) = delete; + z_formatter &operator=(const z_formatter &) = delete; + + void format(const details::log_msg &msg, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + const size_t field_size = 6; + scoped_pad p(field_size, padinfo_, dest); + +#ifdef _WIN32 + int total_minutes = get_cached_offset(msg, tm_time); +#else + // No need to chache under gcc, + // it is very fast (already stored in tm.tm_gmtoff) + (void)(msg); + int total_minutes = os::utc_minutes_offset(tm_time); +#endif + bool is_negative = total_minutes < 0; + if (is_negative) + { + total_minutes = -total_minutes; + dest.push_back('-'); + } + else + { + dest.push_back('+'); + } + + fmt_helper::pad2(total_minutes / 60, dest); // hours + dest.push_back(':'); + fmt_helper::pad2(total_minutes % 60, dest); // minutes + } + +private: + log_clock::time_point last_update_{std::chrono::seconds(0)}; +#ifdef _WIN32 + int offset_minutes_{0}; + + int get_cached_offset(const log_msg &msg, const std::tm &tm_time) + { + if (msg.time - last_update_ >= cache_refresh) + { + offset_minutes_ = os::utc_minutes_offset(tm_time); + last_update_ = msg.time; + } + return offset_minutes_; + } +#endif +}; + +// Thread id +class t_formatter final : public flag_formatter +{ +public: + explicit t_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + if (padinfo_.enabled()) + { + const auto field_size = fmt_helper::count_digits(msg.thread_id); + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::append_int(msg.thread_id, dest); + } + else + { + fmt_helper::append_int(msg.thread_id, dest); + } + } +}; + +// Current pid +class pid_formatter final : public flag_formatter +{ +public: + explicit pid_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &, const std::tm &, fmt::memory_buffer &dest) override + { + const auto pid = static_cast(details::os::pid()); + if (padinfo_.enabled()) + { + auto field_size = fmt_helper::count_digits(pid); + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::append_int(pid, dest); + } + else + { + fmt_helper::append_int(pid, dest); + } + } +}; + +// message counter formatter +class i_formatter final : public flag_formatter +{ +public: + explicit i_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + const size_t field_size = 6; + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::pad6(msg.msg_id, dest); + } +}; + +class v_formatter final : public flag_formatter +{ +public: + explicit v_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + if (padinfo_.enabled()) + { + scoped_pad p(msg.payload, padinfo_, dest); + fmt_helper::append_string_view(msg.payload, dest); + } + else + { + fmt_helper::append_string_view(msg.payload, dest); + } + } +}; + +class ch_formatter final : public flag_formatter +{ +public: + explicit ch_formatter(char ch) + : ch_(ch) + { + } + + void format(const details::log_msg &, const std::tm &, fmt::memory_buffer &dest) override + { + const size_t field_size = 1; + scoped_pad p(field_size, padinfo_, dest); + dest.push_back(ch_); + } + +private: + char ch_; +}; + +// aggregate user chars to display as is +class aggregate_formatter final : public flag_formatter +{ +public: + aggregate_formatter() = default; + + void add_ch(char ch) + { + str_ += ch; + } + void format(const details::log_msg &, const std::tm &, fmt::memory_buffer &dest) override + { + fmt_helper::append_string_view(str_, dest); + } + +private: + std::string str_; +}; + +// mark the color range. expect it to be in the form of "%^colored text%$" +class color_start_formatter final : public flag_formatter +{ +public: + explicit color_start_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + msg.color_range_start = dest.size(); + } +}; +class color_stop_formatter final : public flag_formatter +{ +public: + explicit color_stop_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + msg.color_range_end = dest.size(); + } +}; + +// print source location +class source_location_formatter final : public flag_formatter +{ +public: + explicit source_location_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + if (msg.source.empty()) + { + return; + } + if (padinfo_.enabled()) + { + const auto text_size = std::char_traits::length(msg.source.filename) + fmt_helper::count_digits(msg.source.line) + 1; + scoped_pad p(text_size, padinfo_, dest); + fmt_helper::append_string_view(msg.source.filename, dest); + dest.push_back(':'); + fmt_helper::append_int(msg.source.line, dest); + } + else + { + fmt_helper::append_string_view(msg.source.filename, dest); + dest.push_back(':'); + fmt_helper::append_int(msg.source.line, dest); + } + } +}; +// print source filename +class source_filename_formatter final : public flag_formatter +{ +public: + explicit source_filename_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + if (msg.source.empty()) + { + return; + } + scoped_pad p(msg.source.filename, padinfo_, dest); + fmt_helper::append_string_view(msg.source.filename, dest); + } +}; + +class source_linenum_formatter final : public flag_formatter +{ +public: + explicit source_linenum_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + if (msg.source.empty()) + { + return; + } + if (padinfo_.enabled()) + { + auto field_size = fmt_helper::count_digits(msg.source.line); + scoped_pad p(field_size, padinfo_, dest); + fmt_helper::append_int(msg.source.line, dest); + } + else + { + fmt_helper::append_int(msg.source.line, dest); + } + } +}; +// print source funcname +class source_funcname_formatter final : public flag_formatter +{ +public: + explicit source_funcname_formatter(padding_info padinfo) + : flag_formatter(padinfo){}; + + void format(const details::log_msg &msg, const std::tm &, fmt::memory_buffer &dest) override + { + if (msg.source.empty()) + { + return; + } + scoped_pad p(msg.source.funcname, padinfo_, dest); + fmt_helper::append_string_view(msg.source.funcname, dest); + } +}; + +// Full info formatter +// pattern: [%Y-%m-%d %H:%M:%S.%e] [%n] [%l] %v +class full_formatter final : public flag_formatter +{ +public: + explicit full_formatter(padding_info padinfo) + : flag_formatter(padinfo) + { + } + + void format(const details::log_msg &msg, const std::tm &tm_time, fmt::memory_buffer &dest) override + { + using std::chrono::duration_cast; + using std::chrono::milliseconds; + using std::chrono::seconds; + +#ifndef SPDLOG_NO_DATETIME + + // cache the date/time part for the next second. + auto duration = msg.time.time_since_epoch(); + auto secs = duration_cast(duration); + + if (cache_timestamp_ != secs || cached_datetime_.size() == 0) + { + cached_datetime_.clear(); + cached_datetime_.push_back('['); + fmt_helper::append_int(tm_time.tm_year + 1900, cached_datetime_); + cached_datetime_.push_back('-'); + + fmt_helper::pad2(tm_time.tm_mon + 1, cached_datetime_); + cached_datetime_.push_back('-'); + + fmt_helper::pad2(tm_time.tm_mday, cached_datetime_); + cached_datetime_.push_back(' '); + + fmt_helper::pad2(tm_time.tm_hour, cached_datetime_); + cached_datetime_.push_back(':'); + + fmt_helper::pad2(tm_time.tm_min, cached_datetime_); + cached_datetime_.push_back(':'); + + fmt_helper::pad2(tm_time.tm_sec, cached_datetime_); + cached_datetime_.push_back('.'); + + cache_timestamp_ = secs; + } + fmt_helper::append_buf(cached_datetime_, dest); + + auto millis = fmt_helper::time_fraction(msg.time); + fmt_helper::pad3(static_cast(millis.count()), dest); + dest.push_back(']'); + dest.push_back(' '); + +#else // no datetime needed + (void)tm_time; +#endif + +#ifndef SPDLOG_NO_NAME + if (!msg.logger_name->empty()) + { + dest.push_back('['); + // fmt_helper::append_str(*msg.logger_name, dest); + fmt_helper::append_string_view(*msg.logger_name, dest); + dest.push_back(']'); + dest.push_back(' '); + } +#endif + + dest.push_back('['); + // wrap the level name with color + msg.color_range_start = dest.size(); + // fmt_helper::append_string_view(level::to_c_str(msg.level), dest); + fmt_helper::append_string_view(level::to_string_view(msg.level), dest); + msg.color_range_end = dest.size(); + dest.push_back(']'); + dest.push_back(' '); + + // add source location if present + if (!msg.source.empty()) + { + dest.push_back('['); + fmt_helper::append_string_view(msg.source.filename, dest); + dest.push_back(':'); + fmt_helper::append_int(msg.source.line, dest); + dest.push_back(']'); + dest.push_back(' '); + } + // fmt_helper::append_string_view(msg.msg(), dest); + fmt_helper::append_string_view(msg.payload, dest); + } + +private: + std::chrono::seconds cache_timestamp_{0}; + fmt::basic_memory_buffer cached_datetime_; +}; + +} // namespace details + +class pattern_formatter final : public formatter +{ +public: + explicit pattern_formatter( + std::string pattern, pattern_time_type time_type = pattern_time_type::local, std::string eol = spdlog::details::os::default_eol) + : pattern_(std::move(pattern)) + , eol_(std::move(eol)) + , pattern_time_type_(time_type) + , last_log_secs_(0) + { + std::memset(&cached_tm_, 0, sizeof(cached_tm_)); + compile_pattern_(pattern_); + } + + // use by default full formatter for if pattern is not given + explicit pattern_formatter(pattern_time_type time_type = pattern_time_type::local, std::string eol = spdlog::details::os::default_eol) + : pattern_("%+") + , eol_(std::move(eol)) + , pattern_time_type_(time_type) + , last_log_secs_(0) + { + std::memset(&cached_tm_, 0, sizeof(cached_tm_)); + formatters_.push_back(details::make_unique(details::padding_info{})); + } + + pattern_formatter(const pattern_formatter &other) = delete; + pattern_formatter &operator=(const pattern_formatter &other) = delete; + + std::unique_ptr clone() const override + { + return details::make_unique(pattern_, pattern_time_type_, eol_); + } + + void format(const details::log_msg &msg, fmt::memory_buffer &dest) override + { +#ifndef SPDLOG_NO_DATETIME + auto secs = std::chrono::duration_cast(msg.time.time_since_epoch()); + if (secs != last_log_secs_) + { + cached_tm_ = get_time_(msg); + last_log_secs_ = secs; + } +#endif + for (auto &f : formatters_) + { + f->format(msg, cached_tm_, dest); + } + // write eol + details::fmt_helper::append_string_view(eol_, dest); + } + +private: + std::string pattern_; + std::string eol_; + pattern_time_type pattern_time_type_; + std::tm cached_tm_; + std::chrono::seconds last_log_secs_; + + std::vector> formatters_; + + std::tm get_time_(const details::log_msg &msg) + { + if (pattern_time_type_ == pattern_time_type::local) + { + return details::os::localtime(log_clock::to_time_t(msg.time)); + } + return details::os::gmtime(log_clock::to_time_t(msg.time)); + } + + void handle_flag_(char flag, details::padding_info padding) + { + switch (flag) + { + + case ('+'): // default formatter + formatters_.push_back(details::make_unique(padding)); + break; + + case 'n': // logger name + formatters_.push_back(details::make_unique(padding)); + break; + + case 'l': // level + formatters_.push_back(details::make_unique(padding)); + break; + + case 'L': // short level + formatters_.push_back(details::make_unique(padding)); + break; + + case ('t'): // thread id + formatters_.push_back(details::make_unique(padding)); + break; + + case ('v'): // the message text + formatters_.push_back(details::make_unique(padding)); + break; + + case ('a'): // weekday + formatters_.push_back(details::make_unique(padding)); + break; + + case ('A'): // short weekday + formatters_.push_back(details::make_unique(padding)); + break; + + case ('b'): + case ('h'): // month + formatters_.push_back(details::make_unique(padding)); + break; + + case ('B'): // short month + formatters_.push_back(details::make_unique(padding)); + break; + + case ('c'): // datetime + formatters_.push_back(details::make_unique(padding)); + break; + + case ('C'): // year 2 digits + formatters_.push_back(details::make_unique(padding)); + break; + + case ('Y'): // year 4 digits + formatters_.push_back(details::make_unique(padding)); + break; + + case ('D'): + case ('x'): // datetime MM/DD/YY + formatters_.push_back(details::make_unique(padding)); + break; + + case ('m'): // month 1-12 + formatters_.push_back(details::make_unique(padding)); + break; + + case ('d'): // day of month 1-31 + formatters_.push_back(details::make_unique(padding)); + break; + + case ('H'): // hours 24 + formatters_.push_back(details::make_unique(padding)); + break; + + case ('I'): // hours 12 + formatters_.push_back(details::make_unique(padding)); + break; + + case ('M'): // minutes + formatters_.push_back(details::make_unique(padding)); + break; + + case ('S'): // seconds + formatters_.push_back(details::make_unique(padding)); + break; + + case ('e'): // milliseconds + formatters_.push_back(details::make_unique(padding)); + break; + + case ('f'): // microseconds + formatters_.push_back(details::make_unique(padding)); + break; + + case ('F'): // nanoseconds + formatters_.push_back(details::make_unique(padding)); + break; + + case ('E'): // seconds since epoch + formatters_.push_back(details::make_unique(padding)); + break; + + case ('p'): // am/pm + formatters_.push_back(details::make_unique(padding)); + break; + + case ('r'): // 12 hour clock 02:55:02 pm + formatters_.push_back(details::make_unique(padding)); + break; + + case ('R'): // 24-hour HH:MM time + formatters_.push_back(details::make_unique(padding)); + break; + + case ('T'): + case ('X'): // ISO 8601 time format (HH:MM:SS) + formatters_.push_back(details::make_unique(padding)); + break; + + case ('z'): // timezone + formatters_.push_back(details::make_unique(padding)); + break; + + case ('P'): // pid + formatters_.push_back(details::make_unique(padding)); + break; + +#ifdef SPDLOG_ENABLE_MESSAGE_COUNTER + case ('i'): + formatters_.push_back(details::make_unique(padding)); + break; +#endif + case ('^'): // color range start + formatters_.push_back(details::make_unique(padding)); + break; + + case ('$'): // color range end + formatters_.push_back(details::make_unique(padding)); + break; + + case ('@'): // source location (filename:filenumber) + formatters_.push_back(details::make_unique(padding)); + break; + + case ('s'): // source filename + formatters_.push_back(details::make_unique(padding)); + break; + + case ('#'): // source line number + formatters_.push_back(details::make_unique(padding)); + break; + + case ('!'): // source funcname + formatters_.push_back(details::make_unique(padding)); + break; + + case ('%'): // % char + formatters_.push_back(details::make_unique('%')); + break; + + default: // Unknown flag appears as is + auto unknown_flag = details::make_unique(); + unknown_flag->add_ch('%'); + unknown_flag->add_ch(flag); + formatters_.push_back((std::move(unknown_flag))); + break; + } + } + + // Extract given pad spec (e.g. %8X) + // Advance the given it pass the end of the padding spec found (if any) + // Return padding. + details::padding_info handle_padspec_(std::string::const_iterator &it, std::string::const_iterator end) + { + using details::padding_info; + using details::scoped_pad; + const size_t max_width = 128; + if (it == end) + { + return padding_info{}; + } + + padding_info::pad_side side; + switch (*it) + { + case '-': + side = padding_info::right; + ++it; + break; + case '=': + side = padding_info::center; + ++it; + break; + default: + side = details::padding_info::left; + break; + } + + if (it == end || !std::isdigit(static_cast(*it))) + { + return padding_info{0, side}; + } + + auto width = static_cast(*it - '0'); + for (++it; it != end && std::isdigit(static_cast(*it)); ++it) + { + auto digit = static_cast(*it - '0'); + width = width * 10 + digit; + } + return details::padding_info{std::min(width, max_width), side}; + } + + void compile_pattern_(const std::string &pattern) + { + auto end = pattern.end(); + std::unique_ptr user_chars; + formatters_.clear(); + for (auto it = pattern.begin(); it != end; ++it) + { + if (*it == '%') + { + if (user_chars) // append user chars found so far + { + formatters_.push_back(std::move(user_chars)); + } + + auto padding = handle_padspec_(++it, end); + + if (it != end) + { + handle_flag_(*it, padding); + } + else + { + break; + } + } + else // chars not following the % sign should be displayed as is + { + if (!user_chars) + { + user_chars = details::make_unique(); + } + user_chars->add_ch(*it); + } + } + if (user_chars) // append raw chars found so far + { + formatters_.push_back(std::move(user_chars)); + } + } +}; +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/periodic_worker.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/periodic_worker.h new file mode 100644 index 0000000..fa6488d --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/periodic_worker.h @@ -0,0 +1,71 @@ + +// +// Copyright(c) 2018 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +// periodic worker thread - periodically executes the given callback function. +// +// RAII over the owned thread: +// creates the thread on construction. +// stops and joins the thread on destruction (if the thread is executing a callback, wait for it to finish first). + +#include +#include +#include +#include +#include +namespace spdlog { +namespace details { + +class periodic_worker +{ +public: + periodic_worker(const std::function &callback_fun, std::chrono::seconds interval) + { + active_ = (interval > std::chrono::seconds::zero()); + if (!active_) + { + return; + } + + worker_thread_ = std::thread([this, callback_fun, interval]() { + for (;;) + { + std::unique_lock lock(this->mutex_); + if (this->cv_.wait_for(lock, interval, [this] { return !this->active_; })) + { + return; // active_ == false, so exit this thread + } + callback_fun(); + } + }); + } + + periodic_worker(const periodic_worker &) = delete; + periodic_worker &operator=(const periodic_worker &) = delete; + + // stop the worker thread and join it + ~periodic_worker() + { + if (worker_thread_.joinable()) + { + { + std::lock_guard lock(mutex_); + active_ = false; + } + cv_.notify_one(); + worker_thread_.join(); + } + } + +private: + bool active_; + std::thread worker_thread_; + std::mutex mutex_; + std::condition_variable cv_; +}; +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/registry.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/registry.h new file mode 100644 index 0000000..ccd5395 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/registry.h @@ -0,0 +1,285 @@ +// +// Copyright(c) 2015 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +// Loggers registy of unique name->logger pointer +// An attempt to create a logger with an already existing name will be ignored +// If user requests a non existing logger, nullptr will be returned +// This class is thread safe + +#include "spdlog/common.h" +#include "spdlog/details/periodic_worker.h" +#include "spdlog/logger.h" + +#ifndef SPDLOG_DISABLE_DEFAULT_LOGGER +// support for the default stdout color logger +#ifdef _WIN32 +#include "spdlog/sinks/wincolor_sink.h" +#else +#include "spdlog/sinks/ansicolor_sink.h" +#endif +#endif // SPDLOG_DISABLE_DEFAULT_LOGGER + +#include +#include +#include +#include +#include + +namespace spdlog { +namespace details { +class thread_pool; + +class registry +{ +public: + registry(const registry &) = delete; + registry &operator=(const registry &) = delete; + + void register_logger(std::shared_ptr new_logger) + { + std::lock_guard lock(logger_map_mutex_); + register_logger_(std::move(new_logger)); + } + + void initialize_logger(std::shared_ptr new_logger) + { + std::lock_guard lock(logger_map_mutex_); + new_logger->set_formatter(formatter_->clone()); + + if (err_handler_) + { + new_logger->set_error_handler(err_handler_); + } + + new_logger->set_level(level_); + new_logger->flush_on(flush_level_); + + if (automatic_registration_) + { + register_logger_(std::move(new_logger)); + } + } + + std::shared_ptr get(const std::string &logger_name) + { + std::lock_guard lock(logger_map_mutex_); + auto found = loggers_.find(logger_name); + return found == loggers_.end() ? nullptr : found->second; + } + + std::shared_ptr default_logger() + { + std::lock_guard lock(logger_map_mutex_); + return default_logger_; + } + + // Return raw ptr to the default logger. + // To be used directly by the spdlog default api (e.g. spdlog::info) + // This make the default API faster, but cannot be used concurrently with set_default_logger(). + // e.g do not call set_default_logger() from one thread while calling spdlog::info() from another. + logger *get_default_raw() + { + return default_logger_.get(); + } + + // set default logger. + // default logger is stored in default_logger_ (for faster retrieval) and in the loggers_ map. + void set_default_logger(std::shared_ptr new_default_logger) + { + std::lock_guard lock(logger_map_mutex_); + // remove previous default logger from the map + if (default_logger_ != nullptr) + { + loggers_.erase(default_logger_->name()); + } + if (new_default_logger != nullptr) + { + loggers_[new_default_logger->name()] = new_default_logger; + } + default_logger_ = std::move(new_default_logger); + } + + void set_tp(std::shared_ptr tp) + { + std::lock_guard lock(tp_mutex_); + tp_ = std::move(tp); + } + + std::shared_ptr get_tp() + { + std::lock_guard lock(tp_mutex_); + return tp_; + } + + // Set global formatter. Each sink in each logger will get a clone of this object + void set_formatter(std::unique_ptr formatter) + { + std::lock_guard lock(logger_map_mutex_); + formatter_ = std::move(formatter); + for (auto &l : loggers_) + { + l.second->set_formatter(formatter_->clone()); + } + } + + void set_level(level::level_enum log_level) + { + std::lock_guard lock(logger_map_mutex_); + for (auto &l : loggers_) + { + l.second->set_level(log_level); + } + level_ = log_level; + } + + void flush_on(level::level_enum log_level) + { + std::lock_guard lock(logger_map_mutex_); + for (auto &l : loggers_) + { + l.second->flush_on(log_level); + } + flush_level_ = log_level; + } + + void flush_every(std::chrono::seconds interval) + { + std::lock_guard lock(flusher_mutex_); + std::function clbk = std::bind(®istry::flush_all, this); + periodic_flusher_ = details::make_unique(clbk, interval); + } + + void set_error_handler(log_err_handler handler) + { + std::lock_guard lock(logger_map_mutex_); + for (auto &l : loggers_) + { + l.second->set_error_handler(handler); + } + err_handler_ = handler; + } + + void apply_all(const std::function)> &fun) + { + std::lock_guard lock(logger_map_mutex_); + for (auto &l : loggers_) + { + fun(l.second); + } + } + + void flush_all() + { + std::lock_guard lock(logger_map_mutex_); + for (auto &l : loggers_) + { + l.second->flush(); + } + } + + void drop(const std::string &logger_name) + { + std::lock_guard lock(logger_map_mutex_); + loggers_.erase(logger_name); + if (default_logger_ && default_logger_->name() == logger_name) + { + default_logger_.reset(); + } + } + + void drop_all() + { + std::lock_guard lock(logger_map_mutex_); + loggers_.clear(); + default_logger_.reset(); + } + + // clean all resources and threads started by the registry + void shutdown() + { + { + std::lock_guard lock(flusher_mutex_); + periodic_flusher_.reset(); + } + + drop_all(); + + { + std::lock_guard lock(tp_mutex_); + tp_.reset(); + } + } + + std::recursive_mutex &tp_mutex() + { + return tp_mutex_; + } + + void set_automatic_registration(bool automatic_regsistration) + { + std::lock_guard lock(logger_map_mutex_); + automatic_registration_ = automatic_regsistration; + } + + static registry &instance() + { + static registry s_instance; + return s_instance; + } + +private: + registry() + : formatter_(new pattern_formatter()) + { + +#ifndef SPDLOG_DISABLE_DEFAULT_LOGGER + // create default logger (ansicolor_stdout_sink_mt or wincolor_stdout_sink_mt in windows). +#ifdef _WIN32 + auto color_sink = std::make_shared(); +#else + auto color_sink = std::make_shared(); +#endif + + const char *default_logger_name = ""; + default_logger_ = std::make_shared(default_logger_name, std::move(color_sink)); + loggers_[default_logger_name] = default_logger_; + +#endif // SPDLOG_DISABLE_DEFAULT_LOGGER + } + + ~registry() = default; + + void throw_if_exists_(const std::string &logger_name) + { + if (loggers_.find(logger_name) != loggers_.end()) + { + throw spdlog_ex("logger with name '" + logger_name + "' already exists"); + } + } + + void register_logger_(std::shared_ptr new_logger) + { + auto logger_name = new_logger->name(); + throw_if_exists_(logger_name); + loggers_[logger_name] = std::move(new_logger); + } + + std::mutex logger_map_mutex_, flusher_mutex_; + std::recursive_mutex tp_mutex_; + std::unordered_map> loggers_; + std::unique_ptr formatter_; + level::level_enum level_ = spdlog::logger::default_level(); + level::level_enum flush_level_ = level::off; + log_err_handler err_handler_; + std::shared_ptr tp_; + std::unique_ptr periodic_flusher_; + std::shared_ptr default_logger_; + bool automatic_registration_ = true; +}; + +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/thread_pool.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/thread_pool.h new file mode 100644 index 0000000..3557897 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/details/thread_pool.h @@ -0,0 +1,238 @@ +#pragma once + +#include "spdlog/details/fmt_helper.h" +#include "spdlog/details/log_msg.h" +#include "spdlog/details/mpmc_blocking_q.h" +#include "spdlog/details/os.h" + +#include +#include +#include +#include + +namespace spdlog { +namespace details { + +using async_logger_ptr = std::shared_ptr; + +enum class async_msg_type +{ + log, + flush, + terminate +}; + +// Async msg to move to/from the queue +// Movable only. should never be copied +struct async_msg +{ + async_msg_type msg_type; + level::level_enum level; + log_clock::time_point time; + size_t thread_id; + fmt::basic_memory_buffer raw; + + size_t msg_id; + source_loc source; + async_logger_ptr worker_ptr; + + async_msg() = default; + ~async_msg() = default; + + // should only be moved in or out of the queue.. + async_msg(const async_msg &) = delete; + +// support for vs2013 move +#if defined(_MSC_VER) && _MSC_VER <= 1800 + async_msg(async_msg &&other) SPDLOG_NOEXCEPT : msg_type(other.msg_type), + level(other.level), + time(other.time), + thread_id(other.thread_id), + raw(move(other.raw)), + msg_id(other.msg_id), + source(other.source), + worker_ptr(std::move(other.worker_ptr)) + { + } + + async_msg &operator=(async_msg &&other) SPDLOG_NOEXCEPT + { + msg_type = other.msg_type; + level = other.level; + time = other.time; + thread_id = other.thread_id; + raw = std::move(other.raw); + msg_id = other.msg_id; + source = other.source; + worker_ptr = std::move(other.worker_ptr); + return *this; + } +#else // (_MSC_VER) && _MSC_VER <= 1800 + async_msg(async_msg &&) = default; + async_msg &operator=(async_msg &&) = default; +#endif + + // construct from log_msg with given type + async_msg(async_logger_ptr &&worker, async_msg_type the_type, details::log_msg &m) + : msg_type(the_type) + , level(m.level) + , time(m.time) + , thread_id(m.thread_id) + , msg_id(m.msg_id) + , source(m.source) + , worker_ptr(std::move(worker)) + { + fmt_helper::append_string_view(m.payload, raw); + } + + async_msg(async_logger_ptr &&worker, async_msg_type the_type) + : msg_type(the_type) + , level(level::off) + , time() + , thread_id(0) + , msg_id(0) + , source() + , worker_ptr(std::move(worker)) + { + } + + explicit async_msg(async_msg_type the_type) + : async_msg(nullptr, the_type) + { + } + + // copy into log_msg + log_msg to_log_msg() + { + log_msg msg(&worker_ptr->name(), level, string_view_t(raw.data(), raw.size())); + msg.time = time; + msg.thread_id = thread_id; + msg.msg_id = msg_id; + msg.source = source; + msg.color_range_start = 0; + msg.color_range_end = 0; + return msg; + } +}; + +class thread_pool +{ +public: + using item_type = async_msg; + using q_type = details::mpmc_blocking_queue; + + thread_pool(size_t q_max_items, size_t threads_n) + : q_(q_max_items) + { + // std::cout << "thread_pool() q_size_bytes: " << q_size_bytes << + // "\tthreads_n: " << threads_n << std::endl; + if (threads_n == 0 || threads_n > 1000) + { + throw spdlog_ex("spdlog::thread_pool(): invalid threads_n param (valid " + "range is 1-1000)"); + } + for (size_t i = 0; i < threads_n; i++) + { + threads_.emplace_back(&thread_pool::worker_loop_, this); + } + } + + // message all threads to terminate gracefully join them + ~thread_pool() + { + try + { + for (size_t i = 0; i < threads_.size(); i++) + { + post_async_msg_(async_msg(async_msg_type::terminate), async_overflow_policy::block); + } + + for (auto &t : threads_) + { + t.join(); + } + } + catch (...) + { + } + } + + thread_pool(const thread_pool &) = delete; + thread_pool &operator=(thread_pool &&) = delete; + + void post_log(async_logger_ptr &&worker_ptr, details::log_msg &msg, async_overflow_policy overflow_policy) + { + async_msg async_m(std::move(worker_ptr), async_msg_type::log, msg); + post_async_msg_(std::move(async_m), overflow_policy); + } + + void post_flush(async_logger_ptr &&worker_ptr, async_overflow_policy overflow_policy) + { + post_async_msg_(async_msg(std::move(worker_ptr), async_msg_type::flush), overflow_policy); + } + + size_t overrun_counter() + { + return q_.overrun_counter(); + } + +private: + q_type q_; + + std::vector threads_; + + void post_async_msg_(async_msg &&new_msg, async_overflow_policy overflow_policy) + { + if (overflow_policy == async_overflow_policy::block) + { + q_.enqueue(std::move(new_msg)); + } + else + { + q_.enqueue_nowait(std::move(new_msg)); + } + } + + void worker_loop_() + { + while (process_next_msg_()) {}; + } + + // process next message in the queue + // return true if this thread should still be active (while no terminate msg + // was received) + bool process_next_msg_() + { + async_msg incoming_async_msg; + bool dequeued = q_.dequeue_for(incoming_async_msg, std::chrono::seconds(10)); + if (!dequeued) + { + return true; + } + + switch (incoming_async_msg.msg_type) + { + case async_msg_type::log: + { + auto msg = incoming_async_msg.to_log_msg(); + incoming_async_msg.worker_ptr->backend_log_(msg); + return true; + } + case async_msg_type::flush: + { + incoming_async_msg.worker_ptr->backend_flush_(); + return true; + } + + case async_msg_type::terminate: + { + return false; + } + } + assert(false && "Unexpected async_msg_type"); + return true; + } +}; + +} // namespace details +} // namespace spdlog diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bin_to_hex.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bin_to_hex.h new file mode 100644 index 0000000..3523380 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bin_to_hex.h @@ -0,0 +1,172 @@ +// +// Copyright(c) 2015 Gabi Melman. +// Distributed under the MIT License (http://opensource.org/licenses/MIT) +// + +#pragma once + +// +// Support for logging binary data as hex +// format flags: +// {:X} - print in uppercase. +// {:s} - don't separate each byte with space. +// {:p} - don't print the position on each line start. +// {:n} - don't split the output to lines. + +// +// Examples: +// +// std::vector v(200, 0x0b); +// logger->info("Some buffer {}", spdlog::to_hex(v)); +// char buf[128]; +// logger->info("Some buffer {:X}", spdlog::to_hex(std::begin(buf), std::end(buf))); + +namespace spdlog { +namespace details { + +template +class bytes_range +{ +public: + bytes_range(It range_begin, It range_end) + : begin_(range_begin) + , end_(range_end) + { + } + + It begin() const + { + return begin_; + } + It end() const + { + return end_; + } + +private: + It begin_, end_; +}; +} // namespace details + +// create a bytes_range that wraps the given container +template +inline details::bytes_range to_hex(const Container &container) +{ + static_assert(sizeof(typename Container::value_type) == 1, "sizeof(Container::value_type) != 1"); + using Iter = typename Container::const_iterator; + return details::bytes_range(std::begin(container), std::end(container)); +} + +// create bytes_range from ranges +template +inline details::bytes_range to_hex(const It range_begin, const It range_end) +{ + return details::bytes_range(range_begin, range_end); +} + +} // namespace spdlog + +namespace fmt { + +template +struct formatter> +{ + const std::size_t line_size = 100; + const char delimiter = ' '; + + bool put_newlines = true; + bool put_delimiters = true; + bool use_uppercase = false; + bool put_positions = true; // position on start of each line + + // parse the format string flags + template + auto parse(ParseContext &ctx) -> decltype(ctx.begin()) + { + auto it = ctx.begin(); + while (*it && *it != '}') + { + switch (*it) + { + case 'X': + use_uppercase = true; + break; + case 's': + put_delimiters = false; + break; + case 'p': + put_positions = false; + break; + case 'n': + put_newlines = false; + break; + } + + ++it; + } + return it; + } + + // format the given bytes range as hex + template + auto format(const spdlog::details::bytes_range &the_range, FormatContext &ctx) -> decltype(ctx.out()) + { + SPDLOG_CONSTEXPR const char *hex_upper = "0123456789ABCDEF"; + SPDLOG_CONSTEXPR const char *hex_lower = "0123456789abcdef"; + const char *hex_chars = use_uppercase ? hex_upper : hex_lower; + + std::size_t pos = 0; + std::size_t column = line_size; + auto inserter = ctx.begin(); + + for (auto &item : the_range) + { + auto ch = static_cast(item); + pos++; + + if (put_newlines && column >= line_size) + { + column = put_newline(inserter, pos); + + // put first byte without delimiter in front of it + *inserter++ = hex_chars[(ch >> 4) & 0x0f]; + *inserter++ = hex_chars[ch & 0x0f]; + column += 2; + continue; + } + + if (put_delimiters) + { + *inserter++ = delimiter; + ++column; + } + + *inserter++ = hex_chars[(ch >> 4) & 0x0f]; + *inserter++ = hex_chars[ch & 0x0f]; + column += 2; + } + return inserter; + } + + // put newline(and position header) + // return the next column + template + std::size_t put_newline(It inserter, std::size_t pos) + { +#ifdef _WIN32 + *inserter++ = '\r'; +#endif + *inserter++ = '\n'; + + if (put_positions) + { + fmt::format_to(inserter, "{:<04X}: ", pos - 1); + return 7; + } + else + { + return 1; + } + } +}; +} // namespace fmt diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/LICENSE.rst b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/LICENSE.rst new file mode 100644 index 0000000..eb6be65 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/LICENSE.rst @@ -0,0 +1,23 @@ +Copyright (c) 2012 - 2016, Victor Zverovich + +All rights reserved. + +Redistribution and use in source and binary forms, with or without +modification, are permitted provided that the following conditions are met: + +1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. +2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + +THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND +ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED +WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE +DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR +ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES +(INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; +LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND +ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT +(INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS +SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/chrono.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/chrono.h new file mode 100644 index 0000000..209cdc2 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/chrono.h @@ -0,0 +1,452 @@ +// Formatting library for C++ - chrono support +// +// Copyright (c) 2012 - present, Victor Zverovich +// All rights reserved. +// +// For the license information refer to format.h. + +#ifndef FMT_CHRONO_H_ +#define FMT_CHRONO_H_ + +#include "format.h" +#include "locale.h" + +#include +#include +#include +#include + +FMT_BEGIN_NAMESPACE + +namespace internal{ + +enum class numeric_system { + standard, + // Alternative numeric system, e.g. 十二 instead of 12 in ja_JP locale. + alternative +}; + +// Parses a put_time-like format string and invokes handler actions. +template +FMT_CONSTEXPR const Char *parse_chrono_format( + const Char *begin, const Char *end, Handler &&handler) { + auto ptr = begin; + while (ptr != end) { + auto c = *ptr; + if (c == '}') break; + if (c != '%') { + ++ptr; + continue; + } + if (begin != ptr) + handler.on_text(begin, ptr); + ++ptr; // consume '%' + if (ptr == end) + throw format_error("invalid format"); + c = *ptr++; + switch (c) { + case '%': + handler.on_text(ptr - 1, ptr); + break; + case 'n': { + const char newline[] = "\n"; + handler.on_text(newline, newline + 1); + break; + } + case 't': { + const char tab[] = "\t"; + handler.on_text(tab, tab + 1); + break; + } + // Day of the week: + case 'a': + handler.on_abbr_weekday(); + break; + case 'A': + handler.on_full_weekday(); + break; + case 'w': + handler.on_dec0_weekday(numeric_system::standard); + break; + case 'u': + handler.on_dec1_weekday(numeric_system::standard); + break; + // Month: + case 'b': + handler.on_abbr_month(); + break; + case 'B': + handler.on_full_month(); + break; + // Hour, minute, second: + case 'H': + handler.on_24_hour(numeric_system::standard); + break; + case 'I': + handler.on_12_hour(numeric_system::standard); + break; + case 'M': + handler.on_minute(numeric_system::standard); + break; + case 'S': + handler.on_second(numeric_system::standard); + break; + // Other: + case 'c': + handler.on_datetime(numeric_system::standard); + break; + case 'x': + handler.on_loc_date(numeric_system::standard); + break; + case 'X': + handler.on_loc_time(numeric_system::standard); + break; + case 'D': + handler.on_us_date(); + break; + case 'F': + handler.on_iso_date(); + break; + case 'r': + handler.on_12_hour_time(); + break; + case 'R': + handler.on_24_hour_time(); + break; + case 'T': + handler.on_iso_time(); + break; + case 'p': + handler.on_am_pm(); + break; + case 'z': + handler.on_utc_offset(); + break; + case 'Z': + handler.on_tz_name(); + break; + // Alternative representation: + case 'E': { + if (ptr == end) + throw format_error("invalid format"); + c = *ptr++; + switch (c) { + case 'c': + handler.on_datetime(numeric_system::alternative); + break; + case 'x': + handler.on_loc_date(numeric_system::alternative); + break; + case 'X': + handler.on_loc_time(numeric_system::alternative); + break; + default: + throw format_error("invalid format"); + } + break; + } + case 'O': + if (ptr == end) + throw format_error("invalid format"); + c = *ptr++; + switch (c) { + case 'w': + handler.on_dec0_weekday(numeric_system::alternative); + break; + case 'u': + handler.on_dec1_weekday(numeric_system::alternative); + break; + case 'H': + handler.on_24_hour(numeric_system::alternative); + break; + case 'I': + handler.on_12_hour(numeric_system::alternative); + break; + case 'M': + handler.on_minute(numeric_system::alternative); + break; + case 'S': + handler.on_second(numeric_system::alternative); + break; + default: + throw format_error("invalid format"); + } + break; + default: + throw format_error("invalid format"); + } + begin = ptr; + } + if (begin != ptr) + handler.on_text(begin, ptr); + return ptr; +} + +struct chrono_format_checker { + void report_no_date() { throw format_error("no date"); } + + template + void on_text(const Char *, const Char *) {} + void on_abbr_weekday() { report_no_date(); } + void on_full_weekday() { report_no_date(); } + void on_dec0_weekday(numeric_system) { report_no_date(); } + void on_dec1_weekday(numeric_system) { report_no_date(); } + void on_abbr_month() { report_no_date(); } + void on_full_month() { report_no_date(); } + void on_24_hour(numeric_system) {} + void on_12_hour(numeric_system) {} + void on_minute(numeric_system) {} + void on_second(numeric_system) {} + void on_datetime(numeric_system) { report_no_date(); } + void on_loc_date(numeric_system) { report_no_date(); } + void on_loc_time(numeric_system) { report_no_date(); } + void on_us_date() { report_no_date(); } + void on_iso_date() { report_no_date(); } + void on_12_hour_time() {} + void on_24_hour_time() {} + void on_iso_time() {} + void on_am_pm() {} + void on_utc_offset() { report_no_date(); } + void on_tz_name() { report_no_date(); } +}; + +template +inline int to_int(Int value) { + FMT_ASSERT(value >= (std::numeric_limits::min)() && + value <= (std::numeric_limits::max)(), "invalid value"); + return static_cast(value); +} + +template +struct chrono_formatter { + FormatContext &context; + OutputIt out; + std::chrono::seconds s; + std::chrono::milliseconds ms; + + typedef typename FormatContext::char_type char_type; + + explicit chrono_formatter(FormatContext &ctx, OutputIt o) + : context(ctx), out(o) {} + + int hour() const { return to_int((s.count() / 3600) % 24); } + + int hour12() const { + auto hour = to_int((s.count() / 3600) % 12); + return hour > 0 ? hour : 12; + } + + int minute() const { return to_int((s.count() / 60) % 60); } + int second() const { return to_int(s.count() % 60); } + + std::tm time() const { + auto time = std::tm(); + time.tm_hour = hour(); + time.tm_min = minute(); + time.tm_sec = second(); + return time; + } + + void write(int value, int width) { + typedef typename int_traits::main_type main_type; + main_type n = to_unsigned(value); + int num_digits = internal::count_digits(n); + if (width > num_digits) + out = std::fill_n(out, width - num_digits, '0'); + out = format_decimal(out, n, num_digits); + } + + void format_localized(const tm &time, const char *format) { + auto locale = context.locale().template get(); + auto &facet = std::use_facet>(locale); + std::basic_ostringstream os; + os.imbue(locale); + facet.put(os, os, ' ', &time, format, format + std::strlen(format)); + auto str = os.str(); + std::copy(str.begin(), str.end(), out); + } + + void on_text(const char_type *begin, const char_type *end) { + std::copy(begin, end, out); + } + + // These are not implemented because durations don't have date information. + void on_abbr_weekday() {} + void on_full_weekday() {} + void on_dec0_weekday(numeric_system) {} + void on_dec1_weekday(numeric_system) {} + void on_abbr_month() {} + void on_full_month() {} + void on_datetime(numeric_system) {} + void on_loc_date(numeric_system) {} + void on_loc_time(numeric_system) {} + void on_us_date() {} + void on_iso_date() {} + void on_utc_offset() {} + void on_tz_name() {} + + void on_24_hour(numeric_system ns) { + if (ns == numeric_system::standard) + return write(hour(), 2); + auto time = tm(); + time.tm_hour = hour(); + format_localized(time, "%OH"); + } + + void on_12_hour(numeric_system ns) { + if (ns == numeric_system::standard) + return write(hour12(), 2); + auto time = tm(); + time.tm_hour = hour(); + format_localized(time, "%OI"); + } + + void on_minute(numeric_system ns) { + if (ns == numeric_system::standard) + return write(minute(), 2); + auto time = tm(); + time.tm_min = minute(); + format_localized(time, "%OM"); + } + + void on_second(numeric_system ns) { + if (ns == numeric_system::standard) { + write(second(), 2); + if (ms != std::chrono::milliseconds(0)) { + *out++ = '.'; + write(to_int(ms.count()), 3); + } + return; + } + auto time = tm(); + time.tm_sec = second(); + format_localized(time, "%OS"); + } + + void on_12_hour_time() { format_localized(time(), "%r"); } + + void on_24_hour_time() { + write(hour(), 2); + *out++ = ':'; + write(minute(), 2); + } + + void on_iso_time() { + on_24_hour_time(); + *out++ = ':'; + write(second(), 2); + } + + void on_am_pm() { format_localized(time(), "%p"); } +}; +} // namespace internal + +template FMT_CONSTEXPR const char *get_units() { + return FMT_NULL; +} +template <> FMT_CONSTEXPR const char *get_units() { return "as"; } +template <> FMT_CONSTEXPR const char *get_units() { return "fs"; } +template <> FMT_CONSTEXPR const char *get_units() { return "ps"; } +template <> FMT_CONSTEXPR const char *get_units() { return "ns"; } +template <> FMT_CONSTEXPR const char *get_units() { return "µs"; } +template <> FMT_CONSTEXPR const char *get_units() { return "ms"; } +template <> FMT_CONSTEXPR const char *get_units() { return "cs"; } +template <> FMT_CONSTEXPR const char *get_units() { return "ds"; } +template <> FMT_CONSTEXPR const char *get_units>() { return "s"; } +template <> FMT_CONSTEXPR const char *get_units() { return "das"; } +template <> FMT_CONSTEXPR const char *get_units() { return "hs"; } +template <> FMT_CONSTEXPR const char *get_units() { return "ks"; } +template <> FMT_CONSTEXPR const char *get_units() { return "Ms"; } +template <> FMT_CONSTEXPR const char *get_units() { return "Gs"; } +template <> FMT_CONSTEXPR const char *get_units() { return "Ts"; } +template <> FMT_CONSTEXPR const char *get_units() { return "Ps"; } +template <> FMT_CONSTEXPR const char *get_units() { return "Es"; } +template <> FMT_CONSTEXPR const char *get_units>() { + return "m"; +} +template <> FMT_CONSTEXPR const char *get_units>() { + return "h"; +} + +template +struct formatter, Char> { + private: + align_spec spec; + internal::arg_ref width_ref; + mutable basic_string_view format_str; + typedef std::chrono::duration duration; + + struct spec_handler { + formatter &f; + basic_parse_context &context; + + typedef internal::arg_ref arg_ref_type; + + template + FMT_CONSTEXPR arg_ref_type make_arg_ref(Id arg_id) { + context.check_arg_id(arg_id); + return arg_ref_type(arg_id); + } + + FMT_CONSTEXPR arg_ref_type make_arg_ref(internal::auto_id) { + return arg_ref_type(context.next_arg_id()); + } + + void on_error(const char *msg) { throw format_error(msg); } + void on_fill(Char fill) { f.spec.fill_ = fill; } + void on_align(alignment align) { f.spec.align_ = align; } + void on_width(unsigned width) { f.spec.width_ = width; } + + template + void on_dynamic_width(Id arg_id) { + f.width_ref = make_arg_ref(arg_id); + } + }; + + public: + formatter() : spec() {} + + FMT_CONSTEXPR auto parse(basic_parse_context &ctx) + -> decltype(ctx.begin()) { + auto begin = ctx.begin(), end = ctx.end(); + if (begin == end) return begin; + spec_handler handler{*this, ctx}; + begin = internal::parse_align(begin, end, handler); + if (begin == end) return begin; + begin = internal::parse_width(begin, end, handler); + end = parse_chrono_format(begin, end, internal::chrono_format_checker()); + format_str = basic_string_view(&*begin, internal::to_unsigned(end - begin)); + return end; + } + + template + auto format(const duration &d, FormatContext &ctx) + -> decltype(ctx.out()) { + auto begin = format_str.begin(), end = format_str.end(); + memory_buffer buf; + typedef output_range range; + basic_writer w(range(ctx.out())); + if (begin == end || *begin == '}') { + if (const char *unit = get_units()) + format_to(buf, "{}{}", d.count(), unit); + else if (Period::den == 1) + format_to(buf, "{}[{}]s", d.count(), Period::num); + else + format_to(buf, "{}[{}/{}]s", d.count(), Period::num, Period::den); + internal::handle_dynamic_spec( + spec.width_, width_ref, ctx); + } else { + auto out = std::back_inserter(buf); + internal::chrono_formatter f(ctx, out); + f.s = std::chrono::duration_cast(d); + f.ms = std::chrono::duration_cast(d - f.s); + parse_chrono_format(begin, end, f); + } + w.write(buf.data(), buf.size(), spec); + return w.out(); + } +}; + +FMT_END_NAMESPACE + +#endif // FMT_CHRONO_H_ diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/color.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/color.h new file mode 100644 index 0000000..5db861c --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/color.h @@ -0,0 +1,577 @@ +// Formatting library for C++ - color support +// +// Copyright (c) 2018 - present, Victor Zverovich and fmt contributors +// All rights reserved. +// +// For the license information refer to format.h. + +#ifndef FMT_COLOR_H_ +#define FMT_COLOR_H_ + +#include "format.h" + +FMT_BEGIN_NAMESPACE + +#ifdef FMT_DEPRECATED_COLORS + +// color and (v)print_colored are deprecated. +enum color { black, red, green, yellow, blue, magenta, cyan, white }; +FMT_API void vprint_colored(color c, string_view format, format_args args); +FMT_API void vprint_colored(color c, wstring_view format, wformat_args args); +template +inline void print_colored(color c, string_view format_str, + const Args & ... args) { + vprint_colored(c, format_str, make_format_args(args...)); +} +template +inline void print_colored(color c, wstring_view format_str, + const Args & ... args) { + vprint_colored(c, format_str, make_format_args(args...)); +} + +inline void vprint_colored(color c, string_view format, format_args args) { + char escape[] = "\x1b[30m"; + escape[3] = static_cast('0' + c); + std::fputs(escape, stdout); + vprint(format, args); + std::fputs(internal::data::RESET_COLOR, stdout); +} + +inline void vprint_colored(color c, wstring_view format, wformat_args args) { + wchar_t escape[] = L"\x1b[30m"; + escape[3] = static_cast('0' + c); + std::fputws(escape, stdout); + vprint(format, args); + std::fputws(internal::data::WRESET_COLOR, stdout); +} + +#else + +enum class color : uint32_t { + alice_blue = 0xF0F8FF, // rgb(240,248,255) + antique_white = 0xFAEBD7, // rgb(250,235,215) + aqua = 0x00FFFF, // rgb(0,255,255) + aquamarine = 0x7FFFD4, // rgb(127,255,212) + azure = 0xF0FFFF, // rgb(240,255,255) + beige = 0xF5F5DC, // rgb(245,245,220) + bisque = 0xFFE4C4, // rgb(255,228,196) + black = 0x000000, // rgb(0,0,0) + blanched_almond = 0xFFEBCD, // rgb(255,235,205) + blue = 0x0000FF, // rgb(0,0,255) + blue_violet = 0x8A2BE2, // rgb(138,43,226) + brown = 0xA52A2A, // rgb(165,42,42) + burly_wood = 0xDEB887, // rgb(222,184,135) + cadet_blue = 0x5F9EA0, // rgb(95,158,160) + chartreuse = 0x7FFF00, // rgb(127,255,0) + chocolate = 0xD2691E, // rgb(210,105,30) + coral = 0xFF7F50, // rgb(255,127,80) + cornflower_blue = 0x6495ED, // rgb(100,149,237) + cornsilk = 0xFFF8DC, // rgb(255,248,220) + crimson = 0xDC143C, // rgb(220,20,60) + cyan = 0x00FFFF, // rgb(0,255,255) + dark_blue = 0x00008B, // rgb(0,0,139) + dark_cyan = 0x008B8B, // rgb(0,139,139) + dark_golden_rod = 0xB8860B, // rgb(184,134,11) + dark_gray = 0xA9A9A9, // rgb(169,169,169) + dark_green = 0x006400, // rgb(0,100,0) + dark_khaki = 0xBDB76B, // rgb(189,183,107) + dark_magenta = 0x8B008B, // rgb(139,0,139) + dark_olive_green = 0x556B2F, // rgb(85,107,47) + dark_orange = 0xFF8C00, // rgb(255,140,0) + dark_orchid = 0x9932CC, // rgb(153,50,204) + dark_red = 0x8B0000, // rgb(139,0,0) + dark_salmon = 0xE9967A, // rgb(233,150,122) + dark_sea_green = 0x8FBC8F, // rgb(143,188,143) + dark_slate_blue = 0x483D8B, // rgb(72,61,139) + dark_slate_gray = 0x2F4F4F, // rgb(47,79,79) + dark_turquoise = 0x00CED1, // rgb(0,206,209) + dark_violet = 0x9400D3, // rgb(148,0,211) + deep_pink = 0xFF1493, // rgb(255,20,147) + deep_sky_blue = 0x00BFFF, // rgb(0,191,255) + dim_gray = 0x696969, // rgb(105,105,105) + dodger_blue = 0x1E90FF, // rgb(30,144,255) + fire_brick = 0xB22222, // rgb(178,34,34) + floral_white = 0xFFFAF0, // rgb(255,250,240) + forest_green = 0x228B22, // rgb(34,139,34) + fuchsia = 0xFF00FF, // rgb(255,0,255) + gainsboro = 0xDCDCDC, // rgb(220,220,220) + ghost_white = 0xF8F8FF, // rgb(248,248,255) + gold = 0xFFD700, // rgb(255,215,0) + golden_rod = 0xDAA520, // rgb(218,165,32) + gray = 0x808080, // rgb(128,128,128) + green = 0x008000, // rgb(0,128,0) + green_yellow = 0xADFF2F, // rgb(173,255,47) + honey_dew = 0xF0FFF0, // rgb(240,255,240) + hot_pink = 0xFF69B4, // rgb(255,105,180) + indian_red = 0xCD5C5C, // rgb(205,92,92) + indigo = 0x4B0082, // rgb(75,0,130) + ivory = 0xFFFFF0, // rgb(255,255,240) + khaki = 0xF0E68C, // rgb(240,230,140) + lavender = 0xE6E6FA, // rgb(230,230,250) + lavender_blush = 0xFFF0F5, // rgb(255,240,245) + lawn_green = 0x7CFC00, // rgb(124,252,0) + lemon_chiffon = 0xFFFACD, // rgb(255,250,205) + light_blue = 0xADD8E6, // rgb(173,216,230) + light_coral = 0xF08080, // rgb(240,128,128) + light_cyan = 0xE0FFFF, // rgb(224,255,255) + light_golden_rod_yellow = 0xFAFAD2, // rgb(250,250,210) + light_gray = 0xD3D3D3, // rgb(211,211,211) + light_green = 0x90EE90, // rgb(144,238,144) + light_pink = 0xFFB6C1, // rgb(255,182,193) + light_salmon = 0xFFA07A, // rgb(255,160,122) + light_sea_green = 0x20B2AA, // rgb(32,178,170) + light_sky_blue = 0x87CEFA, // rgb(135,206,250) + light_slate_gray = 0x778899, // rgb(119,136,153) + light_steel_blue = 0xB0C4DE, // rgb(176,196,222) + light_yellow = 0xFFFFE0, // rgb(255,255,224) + lime = 0x00FF00, // rgb(0,255,0) + lime_green = 0x32CD32, // rgb(50,205,50) + linen = 0xFAF0E6, // rgb(250,240,230) + magenta = 0xFF00FF, // rgb(255,0,255) + maroon = 0x800000, // rgb(128,0,0) + medium_aquamarine = 0x66CDAA, // rgb(102,205,170) + medium_blue = 0x0000CD, // rgb(0,0,205) + medium_orchid = 0xBA55D3, // rgb(186,85,211) + medium_purple = 0x9370DB, // rgb(147,112,219) + medium_sea_green = 0x3CB371, // rgb(60,179,113) + medium_slate_blue = 0x7B68EE, // rgb(123,104,238) + medium_spring_green = 0x00FA9A, // rgb(0,250,154) + medium_turquoise = 0x48D1CC, // rgb(72,209,204) + medium_violet_red = 0xC71585, // rgb(199,21,133) + midnight_blue = 0x191970, // rgb(25,25,112) + mint_cream = 0xF5FFFA, // rgb(245,255,250) + misty_rose = 0xFFE4E1, // rgb(255,228,225) + moccasin = 0xFFE4B5, // rgb(255,228,181) + navajo_white = 0xFFDEAD, // rgb(255,222,173) + navy = 0x000080, // rgb(0,0,128) + old_lace = 0xFDF5E6, // rgb(253,245,230) + olive = 0x808000, // rgb(128,128,0) + olive_drab = 0x6B8E23, // rgb(107,142,35) + orange = 0xFFA500, // rgb(255,165,0) + orange_red = 0xFF4500, // rgb(255,69,0) + orchid = 0xDA70D6, // rgb(218,112,214) + pale_golden_rod = 0xEEE8AA, // rgb(238,232,170) + pale_green = 0x98FB98, // rgb(152,251,152) + pale_turquoise = 0xAFEEEE, // rgb(175,238,238) + pale_violet_red = 0xDB7093, // rgb(219,112,147) + papaya_whip = 0xFFEFD5, // rgb(255,239,213) + peach_puff = 0xFFDAB9, // rgb(255,218,185) + peru = 0xCD853F, // rgb(205,133,63) + pink = 0xFFC0CB, // rgb(255,192,203) + plum = 0xDDA0DD, // rgb(221,160,221) + powder_blue = 0xB0E0E6, // rgb(176,224,230) + purple = 0x800080, // rgb(128,0,128) + rebecca_purple = 0x663399, // rgb(102,51,153) + red = 0xFF0000, // rgb(255,0,0) + rosy_brown = 0xBC8F8F, // rgb(188,143,143) + royal_blue = 0x4169E1, // rgb(65,105,225) + saddle_brown = 0x8B4513, // rgb(139,69,19) + salmon = 0xFA8072, // rgb(250,128,114) + sandy_brown = 0xF4A460, // rgb(244,164,96) + sea_green = 0x2E8B57, // rgb(46,139,87) + sea_shell = 0xFFF5EE, // rgb(255,245,238) + sienna = 0xA0522D, // rgb(160,82,45) + silver = 0xC0C0C0, // rgb(192,192,192) + sky_blue = 0x87CEEB, // rgb(135,206,235) + slate_blue = 0x6A5ACD, // rgb(106,90,205) + slate_gray = 0x708090, // rgb(112,128,144) + snow = 0xFFFAFA, // rgb(255,250,250) + spring_green = 0x00FF7F, // rgb(0,255,127) + steel_blue = 0x4682B4, // rgb(70,130,180) + tan = 0xD2B48C, // rgb(210,180,140) + teal = 0x008080, // rgb(0,128,128) + thistle = 0xD8BFD8, // rgb(216,191,216) + tomato = 0xFF6347, // rgb(255,99,71) + turquoise = 0x40E0D0, // rgb(64,224,208) + violet = 0xEE82EE, // rgb(238,130,238) + wheat = 0xF5DEB3, // rgb(245,222,179) + white = 0xFFFFFF, // rgb(255,255,255) + white_smoke = 0xF5F5F5, // rgb(245,245,245) + yellow = 0xFFFF00, // rgb(255,255,0) + yellow_green = 0x9ACD32 // rgb(154,205,50) +}; // enum class color + +enum class terminal_color : uint8_t { + black = 30, + red, + green, + yellow, + blue, + magenta, + cyan, + white, + bright_black = 90, + bright_red, + bright_green, + bright_yellow, + bright_blue, + bright_magenta, + bright_cyan, + bright_white +}; // enum class terminal_color + +enum class emphasis : uint8_t { + bold = 1, + italic = 1 << 1, + underline = 1 << 2, + strikethrough = 1 << 3 +}; // enum class emphasis + +// rgb is a struct for red, green and blue colors. +// We use rgb as name because some editors will show it as color direct in the +// editor. +struct rgb { + FMT_CONSTEXPR_DECL rgb() : r(0), g(0), b(0) {} + FMT_CONSTEXPR_DECL rgb(uint8_t r_, uint8_t g_, uint8_t b_) + : r(r_), g(g_), b(b_) {} + FMT_CONSTEXPR_DECL rgb(uint32_t hex) + : r((hex >> 16) & 0xFF), g((hex >> 8) & 0xFF), b((hex) & 0xFF) {} + FMT_CONSTEXPR_DECL rgb(color hex) + : r((uint32_t(hex) >> 16) & 0xFF), g((uint32_t(hex) >> 8) & 0xFF), + b(uint32_t(hex) & 0xFF) {} + uint8_t r; + uint8_t g; + uint8_t b; +}; + +namespace internal { + +// color is a struct of either a rgb color or a terminal color. +struct color_type { + FMT_CONSTEXPR color_type() FMT_NOEXCEPT + : is_rgb(), value{} {} + FMT_CONSTEXPR color_type(color rgb_color) FMT_NOEXCEPT + : is_rgb(true), value{} { + value.rgb_color = static_cast(rgb_color); + } + FMT_CONSTEXPR color_type(rgb rgb_color) FMT_NOEXCEPT + : is_rgb(true), value{} { + value.rgb_color = (static_cast(rgb_color.r) << 16) + | (static_cast(rgb_color.g) << 8) | rgb_color.b; + } + FMT_CONSTEXPR color_type(terminal_color term_color) FMT_NOEXCEPT + : is_rgb(), value{} { + value.term_color = static_cast(term_color); + } + bool is_rgb; + union color_union { + uint8_t term_color; + uint32_t rgb_color; + } value; +}; +} // namespace internal + +// Experimental text formatting support. +class text_style { + public: + FMT_CONSTEXPR text_style(emphasis em = emphasis()) FMT_NOEXCEPT + : set_foreground_color(), set_background_color(), ems(em) {} + + FMT_CONSTEXPR text_style &operator|=(const text_style &rhs) { + if (!set_foreground_color) { + set_foreground_color = rhs.set_foreground_color; + foreground_color = rhs.foreground_color; + } else if (rhs.set_foreground_color) { + if (!foreground_color.is_rgb || !rhs.foreground_color.is_rgb) + throw format_error("can't OR a terminal color"); + foreground_color.value.rgb_color |= rhs.foreground_color.value.rgb_color; + } + + if (!set_background_color) { + set_background_color = rhs.set_background_color; + background_color = rhs.background_color; + } else if (rhs.set_background_color) { + if (!background_color.is_rgb || !rhs.background_color.is_rgb) + throw format_error("can't OR a terminal color"); + background_color.value.rgb_color |= rhs.background_color.value.rgb_color; + } + + ems = static_cast(static_cast(ems) | + static_cast(rhs.ems)); + return *this; + } + + friend FMT_CONSTEXPR + text_style operator|(text_style lhs, const text_style &rhs) { + return lhs |= rhs; + } + + FMT_CONSTEXPR text_style &operator&=(const text_style &rhs) { + if (!set_foreground_color) { + set_foreground_color = rhs.set_foreground_color; + foreground_color = rhs.foreground_color; + } else if (rhs.set_foreground_color) { + if (!foreground_color.is_rgb || !rhs.foreground_color.is_rgb) + throw format_error("can't AND a terminal color"); + foreground_color.value.rgb_color &= rhs.foreground_color.value.rgb_color; + } + + if (!set_background_color) { + set_background_color = rhs.set_background_color; + background_color = rhs.background_color; + } else if (rhs.set_background_color) { + if (!background_color.is_rgb || !rhs.background_color.is_rgb) + throw format_error("can't AND a terminal color"); + background_color.value.rgb_color &= rhs.background_color.value.rgb_color; + } + + ems = static_cast(static_cast(ems) & + static_cast(rhs.ems)); + return *this; + } + + friend FMT_CONSTEXPR + text_style operator&(text_style lhs, const text_style &rhs) { + return lhs &= rhs; + } + + FMT_CONSTEXPR bool has_foreground() const FMT_NOEXCEPT { + return set_foreground_color; + } + FMT_CONSTEXPR bool has_background() const FMT_NOEXCEPT { + return set_background_color; + } + FMT_CONSTEXPR bool has_emphasis() const FMT_NOEXCEPT { + return static_cast(ems) != 0; + } + FMT_CONSTEXPR internal::color_type get_foreground() const FMT_NOEXCEPT { + assert(has_foreground() && "no foreground specified for this style"); + return foreground_color; + } + FMT_CONSTEXPR internal::color_type get_background() const FMT_NOEXCEPT { + assert(has_background() && "no background specified for this style"); + return background_color; + } + FMT_CONSTEXPR emphasis get_emphasis() const FMT_NOEXCEPT { + assert(has_emphasis() && "no emphasis specified for this style"); + return ems; + } + +private: + FMT_CONSTEXPR text_style(bool is_foreground, + internal::color_type text_color) FMT_NOEXCEPT + : set_foreground_color(), + set_background_color(), + ems() { + if (is_foreground) { + foreground_color = text_color; + set_foreground_color = true; + } else { + background_color = text_color; + set_background_color = true; + } + } + + friend FMT_CONSTEXPR_DECL text_style fg(internal::color_type foreground) + FMT_NOEXCEPT; + friend FMT_CONSTEXPR_DECL text_style bg(internal::color_type background) + FMT_NOEXCEPT; + + internal::color_type foreground_color; + internal::color_type background_color; + bool set_foreground_color; + bool set_background_color; + emphasis ems; +}; + +FMT_CONSTEXPR text_style fg(internal::color_type foreground) FMT_NOEXCEPT { + return text_style(/*is_foreground=*/true, foreground); +} + +FMT_CONSTEXPR text_style bg(internal::color_type background) FMT_NOEXCEPT { + return text_style(/*is_foreground=*/false, background); +} + +FMT_CONSTEXPR text_style operator|(emphasis lhs, emphasis rhs) FMT_NOEXCEPT { + return text_style(lhs) | rhs; +} + +namespace internal { + +template +struct ansi_color_escape { + FMT_CONSTEXPR ansi_color_escape(internal::color_type text_color, + const char * esc) FMT_NOEXCEPT { + // If we have a terminal color, we need to output another escape code + // sequence. + if (!text_color.is_rgb) { + bool is_background = esc == internal::data::BACKGROUND_COLOR; + uint32_t value = text_color.value.term_color; + // Background ASCII codes are the same as the foreground ones but with + // 10 more. + if (is_background) + value += 10u; + + std::size_t index = 0; + buffer[index++] = static_cast('\x1b'); + buffer[index++] = static_cast('['); + + if (value >= 100u) { + buffer[index++] = static_cast('1'); + value %= 100u; + } + buffer[index++] = static_cast('0' + value / 10u); + buffer[index++] = static_cast('0' + value % 10u); + + buffer[index++] = static_cast('m'); + buffer[index++] = static_cast('\0'); + return; + } + + for (int i = 0; i < 7; i++) { + buffer[i] = static_cast(esc[i]); + } + rgb color(text_color.value.rgb_color); + to_esc(color.r, buffer + 7, ';'); + to_esc(color.g, buffer + 11, ';'); + to_esc(color.b, buffer + 15, 'm'); + buffer[19] = static_cast(0); + } + FMT_CONSTEXPR ansi_color_escape(emphasis em) FMT_NOEXCEPT { + uint8_t em_codes[4] = {}; + uint8_t em_bits = static_cast(em); + if (em_bits & static_cast(emphasis::bold)) + em_codes[0] = 1; + if (em_bits & static_cast(emphasis::italic)) + em_codes[1] = 3; + if (em_bits & static_cast(emphasis::underline)) + em_codes[2] = 4; + if (em_bits & static_cast(emphasis::strikethrough)) + em_codes[3] = 9; + + std::size_t index = 0; + for (int i = 0; i < 4; ++i) { + if (!em_codes[i]) + continue; + buffer[index++] = static_cast('\x1b'); + buffer[index++] = static_cast('['); + buffer[index++] = static_cast('0' + em_codes[i]); + buffer[index++] = static_cast('m'); + } + buffer[index++] = static_cast(0); + } + FMT_CONSTEXPR operator const Char *() const FMT_NOEXCEPT { return buffer; } + +private: + Char buffer[7u + 3u * 4u + 1u]; + + static FMT_CONSTEXPR void to_esc(uint8_t c, Char *out, + char delimiter) FMT_NOEXCEPT { + out[0] = static_cast('0' + c / 100); + out[1] = static_cast('0' + c / 10 % 10); + out[2] = static_cast('0' + c % 10); + out[3] = static_cast(delimiter); + } +}; + +template +FMT_CONSTEXPR ansi_color_escape +make_foreground_color(internal::color_type foreground) FMT_NOEXCEPT { + return ansi_color_escape(foreground, internal::data::FOREGROUND_COLOR); +} + +template +FMT_CONSTEXPR ansi_color_escape +make_background_color(internal::color_type background) FMT_NOEXCEPT { + return ansi_color_escape(background, internal::data::BACKGROUND_COLOR); +} + +template +FMT_CONSTEXPR ansi_color_escape +make_emphasis(emphasis em) FMT_NOEXCEPT { + return ansi_color_escape(em); +} + +template +inline void fputs(const Char *chars, FILE *stream) FMT_NOEXCEPT { + std::fputs(chars, stream); +} + +template <> +inline void fputs(const wchar_t *chars, FILE *stream) FMT_NOEXCEPT { + std::fputws(chars, stream); +} + +template +inline void reset_color(FILE *stream) FMT_NOEXCEPT { + fputs(internal::data::RESET_COLOR, stream); +} + +template <> +inline void reset_color(FILE *stream) FMT_NOEXCEPT { + fputs(internal::data::WRESET_COLOR, stream); +} + +// The following specialiazation disables using std::FILE as a character type, +// which is needed because or else +// fmt::print(stderr, fmt::emphasis::bold, ""); +// would take stderr (a std::FILE *) as the format string. +template <> +struct is_string : std::false_type {}; +template <> +struct is_string : std::false_type {}; +} // namespace internal + +template < + typename S, typename Char = typename internal::char_t::type> +void vprint(std::FILE *f, const text_style &ts, const S &format, + basic_format_args::type> args) { + bool has_style = false; + if (ts.has_emphasis()) { + has_style = true; + internal::fputs( + internal::make_emphasis(ts.get_emphasis()), f); + } + if (ts.has_foreground()) { + has_style = true; + internal::fputs( + internal::make_foreground_color(ts.get_foreground()), f); + } + if (ts.has_background()) { + has_style = true; + internal::fputs( + internal::make_background_color(ts.get_background()), f); + } + vprint(f, format, args); + if (has_style) { + internal::reset_color(f); + } +} + +/** + Formats a string and prints it to the specified file stream using ANSI + escape sequences to specify text formatting. + Example: + fmt::print(fmt::emphasis::bold | fg(fmt::color::red), + "Elapsed time: {0:.2f} seconds", 1.23); + */ +template +typename std::enable_if::value>::type print( + std::FILE *f, const text_style &ts, const String &format_str, + const Args &... args) { + internal::check_format_string(format_str); + typedef typename internal::char_t::type char_t; + typedef typename buffer_context::type context_t; + format_arg_store as{args...}; + vprint(f, ts, format_str, basic_format_args(as)); +} + +/** + Formats a string and prints it to stdout using ANSI escape sequences to + specify text formatting. + Example: + fmt::print(fmt::emphasis::bold | fg(fmt::color::red), + "Elapsed time: {0:.2f} seconds", 1.23); + */ +template +typename std::enable_if::value>::type print( + const text_style &ts, const String &format_str, + const Args &... args) { + return print(stdout, ts, format_str, args...); +} + +#endif + +FMT_END_NAMESPACE + +#endif // FMT_COLOR_H_ diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/core.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/core.h new file mode 100644 index 0000000..50b7935 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/core.h @@ -0,0 +1,1502 @@ +// Formatting library for C++ - the core API +// +// Copyright (c) 2012 - present, Victor Zverovich +// All rights reserved. +// +// For the license information refer to format.h. + +#ifndef FMT_CORE_H_ +#define FMT_CORE_H_ + +#include +#include // std::FILE +#include +#include +#include +#include + +// The fmt library version in the form major * 10000 + minor * 100 + patch. +#define FMT_VERSION 50300 + +#ifdef __has_feature +# define FMT_HAS_FEATURE(x) __has_feature(x) +#else +# define FMT_HAS_FEATURE(x) 0 +#endif + +#if defined(__has_include) && !defined(__INTELLISENSE__) && \ + !(defined(__INTEL_COMPILER) && __INTEL_COMPILER < 1600) +# define FMT_HAS_INCLUDE(x) __has_include(x) +#else +# define FMT_HAS_INCLUDE(x) 0 +#endif + +#ifdef __has_cpp_attribute +# define FMT_HAS_CPP_ATTRIBUTE(x) __has_cpp_attribute(x) +#else +# define FMT_HAS_CPP_ATTRIBUTE(x) 0 +#endif + +#if defined(__GNUC__) && !defined(__clang__) +# define FMT_GCC_VERSION (__GNUC__ * 100 + __GNUC_MINOR__) +#else +# define FMT_GCC_VERSION 0 +#endif + +#if __cplusplus >= 201103L || defined(__GXX_EXPERIMENTAL_CXX0X__) +# define FMT_HAS_GXX_CXX11 FMT_GCC_VERSION +#else +# define FMT_HAS_GXX_CXX11 0 +#endif + +#ifdef _MSC_VER +# define FMT_MSC_VER _MSC_VER +#else +# define FMT_MSC_VER 0 +#endif + +// Check if relaxed C++14 constexpr is supported. +// GCC doesn't allow throw in constexpr until version 6 (bug 67371). +#ifndef FMT_USE_CONSTEXPR +# define FMT_USE_CONSTEXPR \ + (FMT_HAS_FEATURE(cxx_relaxed_constexpr) || FMT_MSC_VER >= 1910 || \ + (FMT_GCC_VERSION >= 600 && __cplusplus >= 201402L)) +#endif +#if FMT_USE_CONSTEXPR +# define FMT_CONSTEXPR constexpr +# define FMT_CONSTEXPR_DECL constexpr +#else +# define FMT_CONSTEXPR inline +# define FMT_CONSTEXPR_DECL +#endif + +#ifndef FMT_USE_CONSTEXPR11 +# define FMT_USE_CONSTEXPR11 \ + (FMT_USE_CONSTEXPR || FMT_GCC_VERSION >= 406 || FMT_MSC_VER >= 1900) +#endif +#if FMT_USE_CONSTEXPR11 +# define FMT_CONSTEXPR11 constexpr +#else +# define FMT_CONSTEXPR11 +#endif + +#ifndef FMT_OVERRIDE +# if FMT_HAS_FEATURE(cxx_override) || \ + (FMT_GCC_VERSION >= 408 && FMT_HAS_GXX_CXX11) || FMT_MSC_VER >= 1900 +# define FMT_OVERRIDE override +# else +# define FMT_OVERRIDE +# endif +#endif + +#if FMT_HAS_FEATURE(cxx_explicit_conversions) || \ + FMT_GCC_VERSION >= 405 || FMT_MSC_VER >= 1800 +# define FMT_USE_EXPLICIT 1 +# define FMT_EXPLICIT explicit +#else +# define FMT_USE_EXPLICIT 0 +# define FMT_EXPLICIT +#endif + +#ifndef FMT_NULL +# if FMT_HAS_FEATURE(cxx_nullptr) || \ + (FMT_GCC_VERSION >= 408 && FMT_HAS_GXX_CXX11) || FMT_MSC_VER >= 1600 +# define FMT_NULL nullptr +# define FMT_USE_NULLPTR 1 +# else +# define FMT_NULL NULL +# endif +#endif +#ifndef FMT_USE_NULLPTR +# define FMT_USE_NULLPTR 0 +#endif + +// Check if exceptions are disabled. +#ifndef FMT_EXCEPTIONS +# if (defined(__GNUC__) && !defined(__EXCEPTIONS)) || \ + FMT_MSC_VER && !_HAS_EXCEPTIONS +# define FMT_EXCEPTIONS 0 +# else +# define FMT_EXCEPTIONS 1 +# endif +#endif + +// Define FMT_USE_NOEXCEPT to make fmt use noexcept (C++11 feature). +#ifndef FMT_USE_NOEXCEPT +# define FMT_USE_NOEXCEPT 0 +#endif + +#if FMT_USE_NOEXCEPT || FMT_HAS_FEATURE(cxx_noexcept) || \ + (FMT_GCC_VERSION >= 408 && FMT_HAS_GXX_CXX11) || FMT_MSC_VER >= 1900 +# define FMT_DETECTED_NOEXCEPT noexcept +# define FMT_HAS_CXX11_NOEXCEPT 1 +#else +# define FMT_DETECTED_NOEXCEPT throw() +# define FMT_HAS_CXX11_NOEXCEPT 0 +#endif + +#ifndef FMT_NOEXCEPT +# if FMT_EXCEPTIONS || FMT_HAS_CXX11_NOEXCEPT +# define FMT_NOEXCEPT FMT_DETECTED_NOEXCEPT +# else +# define FMT_NOEXCEPT +# endif +#endif + +#ifndef FMT_BEGIN_NAMESPACE +# if FMT_HAS_FEATURE(cxx_inline_namespaces) || FMT_GCC_VERSION >= 404 || \ + FMT_MSC_VER >= 1900 +# define FMT_INLINE_NAMESPACE inline namespace +# define FMT_END_NAMESPACE }} +# else +# define FMT_INLINE_NAMESPACE namespace +# define FMT_END_NAMESPACE } using namespace v5; } +# endif +# define FMT_BEGIN_NAMESPACE namespace fmt { FMT_INLINE_NAMESPACE v5 { +#endif + +#if !defined(FMT_HEADER_ONLY) && defined(_WIN32) +# ifdef FMT_EXPORT +# define FMT_API __declspec(dllexport) +# elif defined(FMT_SHARED) +# define FMT_API __declspec(dllimport) +# endif +#endif +#ifndef FMT_API +# define FMT_API +#endif + +#ifndef FMT_ASSERT +# define FMT_ASSERT(condition, message) assert((condition) && message) +#endif + +// libc++ supports string_view in pre-c++17. +#if (FMT_HAS_INCLUDE() && \ + (__cplusplus > 201402L || defined(_LIBCPP_VERSION))) || \ + (defined(_MSVC_LANG) && _MSVC_LANG > 201402L && _MSC_VER >= 1910) +# include +# define FMT_STRING_VIEW std::basic_string_view +#elif FMT_HAS_INCLUDE() && __cplusplus >= 201402L +# include +# define FMT_STRING_VIEW std::experimental::basic_string_view +#endif + +// std::result_of is defined in in gcc 4.4. +#if FMT_GCC_VERSION && FMT_GCC_VERSION <= 404 +# include +#endif + +FMT_BEGIN_NAMESPACE +namespace internal { + +// An implementation of declval for pre-C++11 compilers such as gcc 4. +template +typename std::add_rvalue_reference::type declval() FMT_NOEXCEPT; + +template +struct result_of; + +template +struct result_of { + // A workaround for gcc 4.4 that doesn't allow F to be a reference. + typedef typename std::result_of< + typename std::remove_reference::type(Args...)>::type type; +}; + +// Casts nonnegative integer to unsigned. +template +FMT_CONSTEXPR typename std::make_unsigned::type to_unsigned(Int value) { + FMT_ASSERT(value >= 0, "negative value"); + return static_cast::type>(value); +} + +/** A contiguous memory buffer with an optional growing ability. */ +template +class basic_buffer { + private: + basic_buffer(const basic_buffer &) = delete; + void operator=(const basic_buffer &) = delete; + + T *ptr_; + std::size_t size_; + std::size_t capacity_; + + protected: + // Don't initialize ptr_ since it is not accessed to save a few cycles. + basic_buffer(std::size_t sz) FMT_NOEXCEPT: size_(sz), capacity_(sz) {} + + basic_buffer(T *p = FMT_NULL, std::size_t sz = 0, std::size_t cap = 0) + FMT_NOEXCEPT: ptr_(p), size_(sz), capacity_(cap) {} + + /** Sets the buffer data and capacity. */ + void set(T *buf_data, std::size_t buf_capacity) FMT_NOEXCEPT { + ptr_ = buf_data; + capacity_ = buf_capacity; + } + + /** Increases the buffer capacity to hold at least *capacity* elements. */ + virtual void grow(std::size_t capacity) = 0; + + public: + typedef T value_type; + typedef const T &const_reference; + + virtual ~basic_buffer() {} + + T *begin() FMT_NOEXCEPT { return ptr_; } + T *end() FMT_NOEXCEPT { return ptr_ + size_; } + + /** Returns the size of this buffer. */ + std::size_t size() const FMT_NOEXCEPT { return size_; } + + /** Returns the capacity of this buffer. */ + std::size_t capacity() const FMT_NOEXCEPT { return capacity_; } + + /** Returns a pointer to the buffer data. */ + T *data() FMT_NOEXCEPT { return ptr_; } + + /** Returns a pointer to the buffer data. */ + const T *data() const FMT_NOEXCEPT { return ptr_; } + + /** + Resizes the buffer. If T is a POD type new elements may not be initialized. + */ + void resize(std::size_t new_size) { + reserve(new_size); + size_ = new_size; + } + + /** Clears this buffer. */ + void clear() { size_ = 0; } + + /** Reserves space to store at least *capacity* elements. */ + void reserve(std::size_t new_capacity) { + if (new_capacity > capacity_) + grow(new_capacity); + } + + void push_back(const T &value) { + reserve(size_ + 1); + ptr_[size_++] = value; + } + + /** Appends data to the end of the buffer. */ + template + void append(const U *begin, const U *end); + + T &operator[](std::size_t index) { return ptr_[index]; } + const T &operator[](std::size_t index) const { return ptr_[index]; } +}; + +typedef basic_buffer buffer; +typedef basic_buffer wbuffer; + +// A container-backed buffer. +template +class container_buffer : public basic_buffer { + private: + Container &container_; + + protected: + void grow(std::size_t capacity) FMT_OVERRIDE { + container_.resize(capacity); + this->set(&container_[0], capacity); + } + + public: + explicit container_buffer(Container &c) + : basic_buffer(c.size()), container_(c) {} +}; + +// Extracts a reference to the container from back_insert_iterator. +template +inline Container &get_container(std::back_insert_iterator it) { + typedef std::back_insert_iterator bi_iterator; + struct accessor: bi_iterator { + accessor(bi_iterator iter) : bi_iterator(iter) {} + using bi_iterator::container; + }; + return *accessor(it).container; +} + +struct error_handler { + FMT_CONSTEXPR error_handler() {} + FMT_CONSTEXPR error_handler(const error_handler &) {} + + // This function is intentionally not constexpr to give a compile-time error. + FMT_API void on_error(const char *message); +}; + +template +struct no_formatter_error : std::false_type {}; +} // namespace internal + +#if FMT_GCC_VERSION && FMT_GCC_VERSION < 405 +template +struct is_constructible: std::false_type {}; +#else +template +struct is_constructible : std::is_constructible {}; +#endif + +/** + An implementation of ``std::basic_string_view`` for pre-C++17. It provides a + subset of the API. ``fmt::basic_string_view`` is used for format strings even + if ``std::string_view`` is available to prevent issues when a library is + compiled with a different ``-std`` option than the client code (which is not + recommended). + */ +template +class basic_string_view { + private: + const Char *data_; + size_t size_; + + public: + typedef Char char_type; + typedef const Char *iterator; + + FMT_CONSTEXPR basic_string_view() FMT_NOEXCEPT : data_(FMT_NULL), size_(0) {} + + /** Constructs a string reference object from a C string and a size. */ + FMT_CONSTEXPR basic_string_view(const Char *s, size_t count) FMT_NOEXCEPT + : data_(s), size_(count) {} + + /** + \rst + Constructs a string reference object from a C string computing + the size with ``std::char_traits::length``. + \endrst + */ + basic_string_view(const Char *s) + : data_(s), size_(std::char_traits::length(s)) {} + + /** Constructs a string reference from a ``std::basic_string`` object. */ + template + FMT_CONSTEXPR basic_string_view( + const std::basic_string &s) FMT_NOEXCEPT + : data_(s.data()), size_(s.size()) {} + +#ifdef FMT_STRING_VIEW + FMT_CONSTEXPR basic_string_view(FMT_STRING_VIEW s) FMT_NOEXCEPT + : data_(s.data()), size_(s.size()) {} +#endif + + /** Returns a pointer to the string data. */ + FMT_CONSTEXPR const Char *data() const { return data_; } + + /** Returns the string size. */ + FMT_CONSTEXPR size_t size() const { return size_; } + + FMT_CONSTEXPR iterator begin() const { return data_; } + FMT_CONSTEXPR iterator end() const { return data_ + size_; } + + FMT_CONSTEXPR void remove_prefix(size_t n) { + data_ += n; + size_ -= n; + } + + // Lexicographically compare this string reference to other. + int compare(basic_string_view other) const { + size_t str_size = size_ < other.size_ ? size_ : other.size_; + int result = std::char_traits::compare(data_, other.data_, str_size); + if (result == 0) + result = size_ == other.size_ ? 0 : (size_ < other.size_ ? -1 : 1); + return result; + } + + friend bool operator==(basic_string_view lhs, basic_string_view rhs) { + return lhs.compare(rhs) == 0; + } + friend bool operator!=(basic_string_view lhs, basic_string_view rhs) { + return lhs.compare(rhs) != 0; + } + friend bool operator<(basic_string_view lhs, basic_string_view rhs) { + return lhs.compare(rhs) < 0; + } + friend bool operator<=(basic_string_view lhs, basic_string_view rhs) { + return lhs.compare(rhs) <= 0; + } + friend bool operator>(basic_string_view lhs, basic_string_view rhs) { + return lhs.compare(rhs) > 0; + } + friend bool operator>=(basic_string_view lhs, basic_string_view rhs) { + return lhs.compare(rhs) >= 0; + } +}; + +typedef basic_string_view string_view; +typedef basic_string_view wstring_view; + +/** + \rst + The function ``to_string_view`` adapts non-intrusively any kind of string or + string-like type if the user provides a (possibly templated) overload of + ``to_string_view`` which takes an instance of the string class + ``StringType`` and returns a ``fmt::basic_string_view``. + The conversion function must live in the very same namespace as + ``StringType`` to be picked up by ADL. Non-templated string types + like f.e. QString must return a ``basic_string_view`` with a fixed matching + char type. + + **Example**:: + + namespace my_ns { + inline string_view to_string_view(const my_string &s) { + return {s.data(), s.length()}; + } + } + + std::string message = fmt::format(my_string("The answer is {}"), 42); + \endrst + */ +template +inline basic_string_view + to_string_view(basic_string_view s) { return s; } + +template +inline basic_string_view + to_string_view(const std::basic_string &s) { return s; } + +template +inline basic_string_view to_string_view(const Char *s) { return s; } + +#ifdef FMT_STRING_VIEW +template +inline basic_string_view + to_string_view(FMT_STRING_VIEW s) { return s; } +#endif + +// A base class for compile-time strings. It is defined in the fmt namespace to +// make formatting functions visible via ADL, e.g. format(fmt("{}"), 42). +struct compile_string {}; + +template +struct is_compile_string : std::is_base_of {}; + +template < + typename S, + typename Enable = typename std::enable_if::value>::type> +FMT_CONSTEXPR basic_string_view + to_string_view(const S &s) { return s; } + +template +class basic_format_arg; + +template +class basic_format_args; + +// A formatter for objects of type T. +template +struct formatter { + static_assert(internal::no_formatter_error::value, + "don't know how to format the type, include fmt/ostream.h if it provides " + "an operator<< that should be used"); + + // The following functions are not defined intentionally. + template + typename ParseContext::iterator parse(ParseContext &); + template + auto format(const T &val, FormatContext &ctx) -> decltype(ctx.out()); +}; + +template +struct convert_to_int: std::integral_constant< + bool, !std::is_arithmetic::value && std::is_convertible::value> {}; + +namespace internal { + +struct dummy_string_view { typedef void char_type; }; +dummy_string_view to_string_view(...); +using fmt::v5::to_string_view; + +// Specifies whether S is a string type convertible to fmt::basic_string_view. +template +struct is_string : std::integral_constant()))>::value> {}; + +template +struct char_t { + typedef decltype(to_string_view(declval())) result; + typedef typename result::char_type type; +}; + +template +struct named_arg_base; + +template +struct named_arg; + +enum type { + none_type, named_arg_type, + // Integer types should go first, + int_type, uint_type, long_long_type, ulong_long_type, bool_type, char_type, + last_integer_type = char_type, + // followed by floating-point types. + double_type, long_double_type, last_numeric_type = long_double_type, + cstring_type, string_type, pointer_type, custom_type +}; + +FMT_CONSTEXPR bool is_integral(type t) { + FMT_ASSERT(t != internal::named_arg_type, "invalid argument type"); + return t > internal::none_type && t <= internal::last_integer_type; +} + +FMT_CONSTEXPR bool is_arithmetic(type t) { + FMT_ASSERT(t != internal::named_arg_type, "invalid argument type"); + return t > internal::none_type && t <= internal::last_numeric_type; +} + +template +struct string_value { + const Char *value; + std::size_t size; +}; + +template +struct custom_value { + const void *value; + void (*format)(const void *arg, Context &ctx); +}; + +// A formatting argument value. +template +class value { + public: + typedef typename Context::char_type char_type; + + union { + int int_value; + unsigned uint_value; + long long long_long_value; + unsigned long long ulong_long_value; + double double_value; + long double long_double_value; + const void *pointer; + string_value string; + string_value sstring; + string_value ustring; + custom_value custom; + }; + + FMT_CONSTEXPR value(int val = 0) : int_value(val) {} + value(unsigned val) { uint_value = val; } + value(long long val) { long_long_value = val; } + value(unsigned long long val) { ulong_long_value = val; } + value(double val) { double_value = val; } + value(long double val) { long_double_value = val; } + value(const char_type *val) { string.value = val; } + value(const signed char *val) { + static_assert(std::is_same::value, + "incompatible string types"); + sstring.value = val; + } + value(const unsigned char *val) { + static_assert(std::is_same::value, + "incompatible string types"); + ustring.value = val; + } + value(basic_string_view val) { + string.value = val.data(); + string.size = val.size(); + } + value(const void *val) { pointer = val; } + + template + explicit value(const T &val) { + custom.value = &val; + custom.format = &format_custom_arg; + } + + const named_arg_base &as_named_arg() { + return *static_cast*>(pointer); + } + + private: + // Formats an argument of a custom type, such as a user-defined class. + template + static void format_custom_arg(const void *arg, Context &ctx) { + // Get the formatter type through the context to allow different contexts + // have different extension points, e.g. `formatter` for `format` and + // `printf_formatter` for `printf`. + typename Context::template formatter_type::type f; + auto &&parse_ctx = ctx.parse_context(); + parse_ctx.advance_to(f.parse(parse_ctx)); + ctx.advance_to(f.format(*static_cast(arg), ctx)); + } +}; + +// Value initializer used to delay conversion to value and reduce memory churn. +template +struct init { + T val; + static const type type_tag = TYPE; + + FMT_CONSTEXPR init(const T &v) : val(v) {} + FMT_CONSTEXPR operator value() const { return value(val); } +}; + +template +FMT_CONSTEXPR basic_format_arg make_arg(const T &value); + +#define FMT_MAKE_VALUE(TAG, ArgType, ValueType) \ + template \ + FMT_CONSTEXPR init make_value(ArgType val) { \ + return static_cast(val); \ + } + +#define FMT_MAKE_VALUE_SAME(TAG, Type) \ + template \ + FMT_CONSTEXPR init make_value(Type val) { return val; } + +FMT_MAKE_VALUE(bool_type, bool, int) +FMT_MAKE_VALUE(int_type, short, int) +FMT_MAKE_VALUE(uint_type, unsigned short, unsigned) +FMT_MAKE_VALUE_SAME(int_type, int) +FMT_MAKE_VALUE_SAME(uint_type, unsigned) + +// To minimize the number of types we need to deal with, long is translated +// either to int or to long long depending on its size. +typedef std::conditional::type + long_type; +FMT_MAKE_VALUE( + (sizeof(long) == sizeof(int) ? int_type : long_long_type), long, long_type) +typedef std::conditional::type ulong_type; +FMT_MAKE_VALUE( + (sizeof(unsigned long) == sizeof(unsigned) ? uint_type : ulong_long_type), + unsigned long, ulong_type) + +FMT_MAKE_VALUE_SAME(long_long_type, long long) +FMT_MAKE_VALUE_SAME(ulong_long_type, unsigned long long) +FMT_MAKE_VALUE(int_type, signed char, int) +FMT_MAKE_VALUE(uint_type, unsigned char, unsigned) + +// This doesn't use FMT_MAKE_VALUE because of ambiguity in gcc 4.4. +template +FMT_CONSTEXPR typename std::enable_if< + std::is_same::value, + init>::type make_value(Char val) { return val; } + +template +FMT_CONSTEXPR typename std::enable_if< + !std::is_same::value, + init>::type make_value(char val) { return val; } + +FMT_MAKE_VALUE(double_type, float, double) +FMT_MAKE_VALUE_SAME(double_type, double) +FMT_MAKE_VALUE_SAME(long_double_type, long double) + +// Formatting of wide strings into a narrow buffer and multibyte strings +// into a wide buffer is disallowed (https://github.com/fmtlib/fmt/pull/606). +FMT_MAKE_VALUE(cstring_type, typename C::char_type*, + const typename C::char_type*) +FMT_MAKE_VALUE(cstring_type, const typename C::char_type*, + const typename C::char_type*) + +FMT_MAKE_VALUE(cstring_type, signed char*, const signed char*) +FMT_MAKE_VALUE_SAME(cstring_type, const signed char*) +FMT_MAKE_VALUE(cstring_type, unsigned char*, const unsigned char*) +FMT_MAKE_VALUE_SAME(cstring_type, const unsigned char*) +FMT_MAKE_VALUE_SAME(string_type, basic_string_view) +FMT_MAKE_VALUE(string_type, + typename basic_string_view::type, + basic_string_view) +FMT_MAKE_VALUE(string_type, const std::basic_string&, + basic_string_view) +FMT_MAKE_VALUE(pointer_type, void*, const void*) +FMT_MAKE_VALUE_SAME(pointer_type, const void*) + +#if FMT_USE_NULLPTR +FMT_MAKE_VALUE(pointer_type, std::nullptr_t, const void*) +#endif + +// Formatting of arbitrary pointers is disallowed. If you want to output a +// pointer cast it to "void *" or "const void *". In particular, this forbids +// formatting of "[const] volatile char *" which is printed as bool by +// iostreams. +template +typename std::enable_if::value>::type + make_value(const T *) { + static_assert(!sizeof(T), "formatting of non-void pointers is disallowed"); +} + +template +inline typename std::enable_if< + std::is_enum::value && convert_to_int::value, + init>::type + make_value(const T &val) { return static_cast(val); } + +template +inline typename std::enable_if< + is_constructible, T>::value && + !internal::is_string::value, + init, string_type>>::type + make_value(const T &val) { return basic_string_view(val); } + +template +inline typename std::enable_if< + !convert_to_int::value && !std::is_same::value && + !std::is_convertible>::value && + !is_constructible, T>::value && + !internal::is_string::value, + // Implicit conversion to std::string is not handled here because it's + // unsafe: https://github.com/fmtlib/fmt/issues/729 + init>::type + make_value(const T &val) { return val; } + +template +init + make_value(const named_arg &val) { + basic_format_arg arg = make_arg(val.value); + std::memcpy(val.data, &arg, sizeof(arg)); + return static_cast(&val); +} + +template +FMT_CONSTEXPR11 typename std::enable_if< + internal::is_string::value, + init, string_type>>::type + make_value(const S &val) { + // Handle adapted strings. + static_assert(std::is_same< + typename C::char_type, typename internal::char_t::type>::value, + "mismatch between char-types of context and argument"); + return to_string_view(val); +} + +// Maximum number of arguments with packed types. +enum { max_packed_args = 15 }; +enum : unsigned long long { is_unpacked_bit = 1ull << 63 }; + +template +class arg_map; +} // namespace internal + +// A formatting argument. It is a trivially copyable/constructible type to +// allow storage in basic_memory_buffer. +template +class basic_format_arg { + private: + internal::value value_; + internal::type type_; + + template + friend FMT_CONSTEXPR basic_format_arg + internal::make_arg(const T &value); + + template + friend FMT_CONSTEXPR typename internal::result_of::type + visit_format_arg(Visitor &&vis, const basic_format_arg &arg); + + friend class basic_format_args; + friend class internal::arg_map; + + typedef typename Context::char_type char_type; + + public: + class handle { + public: + explicit handle(internal::custom_value custom): custom_(custom) {} + + void format(Context &ctx) const { custom_.format(custom_.value, ctx); } + + private: + internal::custom_value custom_; + }; + + FMT_CONSTEXPR basic_format_arg() : type_(internal::none_type) {} + + FMT_EXPLICIT operator bool() const FMT_NOEXCEPT { + return type_ != internal::none_type; + } + + internal::type type() const { return type_; } + + bool is_integral() const { return internal::is_integral(type_); } + bool is_arithmetic() const { return internal::is_arithmetic(type_); } +}; + +struct monostate {}; + +/** + \rst + Visits an argument dispatching to the appropriate visit method based on + the argument type. For example, if the argument type is ``double`` then + ``vis(value)`` will be called with the value of type ``double``. + \endrst + */ +template +FMT_CONSTEXPR typename internal::result_of::type + visit_format_arg(Visitor &&vis, const basic_format_arg &arg) { + typedef typename Context::char_type char_type; + switch (arg.type_) { + case internal::none_type: + break; + case internal::named_arg_type: + FMT_ASSERT(false, "invalid argument type"); + break; + case internal::int_type: + return vis(arg.value_.int_value); + case internal::uint_type: + return vis(arg.value_.uint_value); + case internal::long_long_type: + return vis(arg.value_.long_long_value); + case internal::ulong_long_type: + return vis(arg.value_.ulong_long_value); + case internal::bool_type: + return vis(arg.value_.int_value != 0); + case internal::char_type: + return vis(static_cast(arg.value_.int_value)); + case internal::double_type: + return vis(arg.value_.double_value); + case internal::long_double_type: + return vis(arg.value_.long_double_value); + case internal::cstring_type: + return vis(arg.value_.string.value); + case internal::string_type: + return vis(basic_string_view( + arg.value_.string.value, arg.value_.string.size)); + case internal::pointer_type: + return vis(arg.value_.pointer); + case internal::custom_type: + return vis(typename basic_format_arg::handle(arg.value_.custom)); + } + return vis(monostate()); +} + +// DEPRECATED! +template +FMT_CONSTEXPR typename internal::result_of::type + visit(Visitor &&vis, const basic_format_arg &arg) { + return visit_format_arg(std::forward(vis), arg); +} + +// Parsing context consisting of a format string range being parsed and an +// argument counter for automatic indexing. +template +class basic_parse_context : private ErrorHandler { + private: + basic_string_view format_str_; + int next_arg_id_; + + public: + typedef Char char_type; + typedef typename basic_string_view::iterator iterator; + + explicit FMT_CONSTEXPR basic_parse_context( + basic_string_view format_str, ErrorHandler eh = ErrorHandler()) + : ErrorHandler(eh), format_str_(format_str), next_arg_id_(0) {} + + // Returns an iterator to the beginning of the format string range being + // parsed. + FMT_CONSTEXPR iterator begin() const FMT_NOEXCEPT { + return format_str_.begin(); + } + + // Returns an iterator past the end of the format string range being parsed. + FMT_CONSTEXPR iterator end() const FMT_NOEXCEPT { return format_str_.end(); } + + // Advances the begin iterator to ``it``. + FMT_CONSTEXPR void advance_to(iterator it) { + format_str_.remove_prefix(internal::to_unsigned(it - begin())); + } + + // Returns the next argument index. + FMT_CONSTEXPR unsigned next_arg_id(); + + FMT_CONSTEXPR bool check_arg_id(unsigned) { + if (next_arg_id_ > 0) { + on_error("cannot switch from automatic to manual argument indexing"); + return false; + } + next_arg_id_ = -1; + return true; + } + void check_arg_id(basic_string_view) {} + + FMT_CONSTEXPR void on_error(const char *message) { + ErrorHandler::on_error(message); + } + + FMT_CONSTEXPR ErrorHandler error_handler() const { return *this; } +}; + +typedef basic_parse_context format_parse_context; +typedef basic_parse_context wformat_parse_context; + +// DEPRECATED! +typedef basic_parse_context parse_context; +typedef basic_parse_context wparse_context; + +namespace internal { +// A map from argument names to their values for named arguments. +template +class arg_map { + private: + arg_map(const arg_map &) = delete; + void operator=(const arg_map &) = delete; + + typedef typename Context::char_type char_type; + + struct entry { + basic_string_view name; + basic_format_arg arg; + }; + + entry *map_; + unsigned size_; + + void push_back(value val) { + const internal::named_arg_base &named = val.as_named_arg(); + map_[size_] = entry{named.name, named.template deserialize()}; + ++size_; + } + + public: + arg_map() : map_(FMT_NULL), size_(0) {} + void init(const basic_format_args &args); + ~arg_map() { delete [] map_; } + + basic_format_arg find(basic_string_view name) const { + // The list is unsorted, so just return the first matching name. + for (entry *it = map_, *end = map_ + size_; it != end; ++it) { + if (it->name == name) + return it->arg; + } + return {}; + } +}; + +// A type-erased reference to an std::locale to avoid heavy include. +class locale_ref { + private: + const void *locale_; // A type-erased pointer to std::locale. + friend class locale; + + public: + locale_ref() : locale_(FMT_NULL) {} + + template + explicit locale_ref(const Locale &loc); + + template + Locale get() const; +}; + +template +class context_base { + public: + typedef OutputIt iterator; + + private: + basic_parse_context parse_context_; + iterator out_; + basic_format_args args_; + locale_ref loc_; + + protected: + typedef Char char_type; + typedef basic_format_arg format_arg; + + context_base(OutputIt out, basic_string_view format_str, + basic_format_args ctx_args, + locale_ref loc = locale_ref()) + : parse_context_(format_str), out_(out), args_(ctx_args), loc_(loc) {} + + // Returns the argument with specified index. + format_arg do_get_arg(unsigned arg_id) { + format_arg arg = args_.get(arg_id); + if (!arg) + parse_context_.on_error("argument index out of range"); + return arg; + } + + // Checks if manual indexing is used and returns the argument with + // specified index. + format_arg get_arg(unsigned arg_id) { + return this->parse_context().check_arg_id(arg_id) ? + this->do_get_arg(arg_id) : format_arg(); + } + + public: + basic_parse_context &parse_context() { return parse_context_; } + basic_format_args args() const { return args_; } // DEPRECATED! + basic_format_arg arg(unsigned id) const { return args_.get(id); } + + internal::error_handler error_handler() { + return parse_context_.error_handler(); + } + + void on_error(const char *message) { parse_context_.on_error(message); } + + // Returns an iterator to the beginning of the output range. + iterator out() { return out_; } + iterator begin() { return out_; } // deprecated + + // Advances the begin iterator to ``it``. + void advance_to(iterator it) { out_ = it; } + + locale_ref locale() { return loc_; } +}; + +template +struct get_type { + typedef decltype(make_value( + declval::type&>())) value_type; + static const type value = value_type::type_tag; +}; + +template +FMT_CONSTEXPR11 unsigned long long get_types() { return 0; } + +template +FMT_CONSTEXPR11 unsigned long long get_types() { + return get_type::value | (get_types() << 4); +} + +template +FMT_CONSTEXPR basic_format_arg make_arg(const T &value) { + basic_format_arg arg; + arg.type_ = get_type::value; + arg.value_ = make_value(value); + return arg; +} + +template +inline typename std::enable_if>::type + make_arg(const T &value) { + return make_value(value); +} + +template +inline typename std::enable_if>::type + make_arg(const T &value) { + return make_arg(value); +} +} // namespace internal + +// Formatting context. +template +class basic_format_context : + public internal::context_base< + OutputIt, basic_format_context, Char> { + public: + /** The character type for the output. */ + typedef Char char_type; + + // using formatter_type = formatter; + template + struct formatter_type { typedef formatter type; }; + + private: + internal::arg_map map_; + + basic_format_context(const basic_format_context &) = delete; + void operator=(const basic_format_context &) = delete; + + typedef internal::context_base base; + typedef typename base::format_arg format_arg; + using base::get_arg; + + public: + using typename base::iterator; + + /** + Constructs a ``basic_format_context`` object. References to the arguments are + stored in the object so make sure they have appropriate lifetimes. + */ + basic_format_context(OutputIt out, basic_string_view format_str, + basic_format_args ctx_args, + internal::locale_ref loc = internal::locale_ref()) + : base(out, format_str, ctx_args, loc) {} + + format_arg next_arg() { + return this->do_get_arg(this->parse_context().next_arg_id()); + } + format_arg get_arg(unsigned arg_id) { return this->do_get_arg(arg_id); } + + // Checks if manual indexing is used and returns the argument with the + // specified name. + format_arg get_arg(basic_string_view name); +}; + +template +struct buffer_context { + typedef basic_format_context< + std::back_insert_iterator>, Char> type; +}; +typedef buffer_context::type format_context; +typedef buffer_context::type wformat_context; + +/** + \rst + An array of references to arguments. It can be implicitly converted into + `~fmt::basic_format_args` for passing into type-erased formatting functions + such as `~fmt::vformat`. + \endrst + */ +template +class format_arg_store { + private: + static const size_t NUM_ARGS = sizeof...(Args); + + // Packed is a macro on MinGW so use IS_PACKED instead. + static const bool IS_PACKED = NUM_ARGS < internal::max_packed_args; + + typedef typename std::conditional, basic_format_arg>::type value_type; + + // If the arguments are not packed, add one more element to mark the end. + static const size_t DATA_SIZE = + NUM_ARGS + (IS_PACKED && NUM_ARGS != 0 ? 0 : 1); + value_type data_[DATA_SIZE]; + + friend class basic_format_args; + + static FMT_CONSTEXPR11 unsigned long long get_types() { + return IS_PACKED ? + internal::get_types() : + internal::is_unpacked_bit | NUM_ARGS; + } + + public: +#if FMT_USE_CONSTEXPR11 + static FMT_CONSTEXPR11 unsigned long long TYPES = get_types(); +#else + static const unsigned long long TYPES; +#endif + +#if (FMT_GCC_VERSION && FMT_GCC_VERSION <= 405) || \ + (FMT_MSC_VER && FMT_MSC_VER <= 1800) + // Workaround array initialization issues in gcc <= 4.5 and MSVC <= 2013. + format_arg_store(const Args &... args) { + value_type init[DATA_SIZE] = + {internal::make_arg(args)...}; + std::memcpy(data_, init, sizeof(init)); + } +#else + format_arg_store(const Args &... args) + : data_{internal::make_arg(args)...} {} +#endif +}; + +#if !FMT_USE_CONSTEXPR11 +template +const unsigned long long format_arg_store::TYPES = + get_types(); +#endif + +/** + \rst + Constructs an `~fmt::format_arg_store` object that contains references to + arguments and can be implicitly converted to `~fmt::format_args`. `Context` + can be omitted in which case it defaults to `~fmt::context`. + \endrst + */ +template +inline format_arg_store + make_format_args(const Args &... args) { return {args...}; } + +/** Formatting arguments. */ +template +class basic_format_args { + public: + typedef unsigned size_type; + typedef basic_format_arg format_arg; + + private: + // To reduce compiled code size per formatting function call, types of first + // max_packed_args arguments are passed in the types_ field. + unsigned long long types_; + union { + // If the number of arguments is less than max_packed_args, the argument + // values are stored in values_, otherwise they are stored in args_. + // This is done to reduce compiled code size as storing larger objects + // may require more code (at least on x86-64) even if the same amount of + // data is actually copied to stack. It saves ~10% on the bloat test. + const internal::value *values_; + const format_arg *args_; + }; + + bool is_packed() const { return (types_ & internal::is_unpacked_bit) == 0; } + + typename internal::type type(unsigned index) const { + unsigned shift = index * 4; + return static_cast( + (types_ & (0xfull << shift)) >> shift); + } + + friend class internal::arg_map; + + void set_data(const internal::value *values) { values_ = values; } + void set_data(const format_arg *args) { args_ = args; } + + format_arg do_get(size_type index) const { + format_arg arg; + if (!is_packed()) { + auto num_args = max_size(); + if (index < num_args) + arg = args_[index]; + return arg; + } + if (index > internal::max_packed_args) + return arg; + arg.type_ = type(index); + if (arg.type_ == internal::none_type) + return arg; + internal::value &val = arg.value_; + val = values_[index]; + return arg; + } + + public: + basic_format_args() : types_(0) {} + + /** + \rst + Constructs a `basic_format_args` object from `~fmt::format_arg_store`. + \endrst + */ + template + basic_format_args(const format_arg_store &store) + : types_(static_cast(store.TYPES)) { + set_data(store.data_); + } + + /** + \rst + Constructs a `basic_format_args` object from a dynamic set of arguments. + \endrst + */ + basic_format_args(const format_arg *args, size_type count) + : types_(internal::is_unpacked_bit | count) { + set_data(args); + } + + /** Returns the argument at specified index. */ + format_arg get(size_type index) const { + format_arg arg = do_get(index); + if (arg.type_ == internal::named_arg_type) + arg = arg.value_.as_named_arg().template deserialize(); + return arg; + } + + size_type max_size() const { + unsigned long long max_packed = internal::max_packed_args; + return static_cast( + is_packed() ? max_packed : types_ & ~internal::is_unpacked_bit); + } +}; + +/** An alias to ``basic_format_args``. */ +// It is a separate type rather than a typedef to make symbols readable. +struct format_args : basic_format_args { + template + format_args(Args &&... arg) + : basic_format_args(std::forward(arg)...) {} +}; +struct wformat_args : basic_format_args { + template + wformat_args(Args &&... arg) + : basic_format_args(std::forward(arg)...) {} +}; + +#define FMT_ENABLE_IF_T(B, T) typename std::enable_if::type + +#ifndef FMT_USE_ALIAS_TEMPLATES +# define FMT_USE_ALIAS_TEMPLATES FMT_HAS_FEATURE(cxx_alias_templates) +#endif +#if FMT_USE_ALIAS_TEMPLATES +/** String's character type. */ +template +using char_t = FMT_ENABLE_IF_T( + internal::is_string::value, typename internal::char_t::type); +#define FMT_CHAR(S) fmt::char_t +#else +template +struct char_t : std::enable_if< + internal::is_string::value, typename internal::char_t::type> {}; +#define FMT_CHAR(S) typename char_t::type +#endif + +namespace internal { +template +struct named_arg_base { + basic_string_view name; + + // Serialized value. + mutable char data[ + sizeof(basic_format_arg::type>)]; + + named_arg_base(basic_string_view nm) : name(nm) {} + + template + basic_format_arg deserialize() const { + basic_format_arg arg; + std::memcpy(&arg, data, sizeof(basic_format_arg)); + return arg; + } +}; + +template +struct named_arg : named_arg_base { + const T &value; + + named_arg(basic_string_view name, const T &val) + : named_arg_base(name), value(val) {} +}; + +template +inline typename std::enable_if::value>::type + check_format_string(const S &) {} +template +typename std::enable_if::value>::type + check_format_string(S); + +template +struct checked_args : format_arg_store< + typename buffer_context::type, Args...> { + typedef typename buffer_context::type context; + + checked_args(const S &format_str, const Args &... args): + format_arg_store(args...) { + internal::check_format_string(format_str); + } + + basic_format_args operator*() const { return *this; } +}; + +template +std::basic_string vformat( + basic_string_view format_str, + basic_format_args::type> args); + +template +typename buffer_context::type::iterator vformat_to( + internal::basic_buffer &buf, basic_string_view format_str, + basic_format_args::type> args); +} + +/** + \rst + Returns a named argument to be used in a formatting function. + + **Example**:: + + fmt::print("Elapsed time: {s:.2f} seconds", fmt::arg("s", 1.23)); + \endrst + */ +template +inline internal::named_arg arg(string_view name, const T &arg) { + return {name, arg}; +} + +template +inline internal::named_arg arg(wstring_view name, const T &arg) { + return {name, arg}; +} + +// Disable nested named arguments, e.g. ``arg("a", arg("b", 42))``. +template +void arg(S, internal::named_arg) = delete; + +template +struct is_contiguous: std::false_type {}; + +template +struct is_contiguous >: std::true_type {}; + +template +struct is_contiguous >: std::true_type {}; + +/** Formats a string and writes the output to ``out``. */ +template +typename std::enable_if< + is_contiguous::value, std::back_insert_iterator>::type + vformat_to( + std::back_insert_iterator out, + const S &format_str, + basic_format_args::type> args) { + internal::container_buffer buf(internal::get_container(out)); + internal::vformat_to(buf, to_string_view(format_str), args); + return out; +} + +template +inline typename std::enable_if< + is_contiguous::value && internal::is_string::value, + std::back_insert_iterator>::type + format_to(std::back_insert_iterator out, const S &format_str, + const Args &... args) { + internal::checked_args ca(format_str, args...); + return vformat_to(out, to_string_view(format_str), *ca); +} + +template +inline std::basic_string vformat( + const S &format_str, + basic_format_args::type> args) { + return internal::vformat(to_string_view(format_str), args); +} + +/** + \rst + Formats arguments and returns the result as a string. + + **Example**:: + + #include + std::string message = fmt::format("The answer is {}", 42); + \endrst +*/ +template +inline std::basic_string format( + const S &format_str, const Args &... args) { + return internal::vformat( + to_string_view(format_str), + *internal::checked_args(format_str, args...)); +} + +FMT_API void vprint(std::FILE *f, string_view format_str, format_args args); +FMT_API void vprint(std::FILE *f, wstring_view format_str, wformat_args args); + +/** + \rst + Prints formatted data to the file *f*. For wide format strings, + *f* should be in wide-oriented mode set via ``fwide(f, 1)`` or + ``_setmode(_fileno(f), _O_U8TEXT)`` on Windows. + + **Example**:: + + fmt::print(stderr, "Don't {}!", "panic"); + \endrst + */ +template +inline FMT_ENABLE_IF_T(internal::is_string::value, void) + print(std::FILE *f, const S &format_str, const Args &... args) { + vprint(f, to_string_view(format_str), + internal::checked_args(format_str, args...)); +} + +FMT_API void vprint(string_view format_str, format_args args); +FMT_API void vprint(wstring_view format_str, wformat_args args); + +/** + \rst + Prints formatted data to ``stdout``. + + **Example**:: + + fmt::print("Elapsed time: {0:.2f} seconds", 1.23); + \endrst + */ +template +inline FMT_ENABLE_IF_T(internal::is_string::value, void) + print(const S &format_str, const Args &... args) { + vprint(to_string_view(format_str), + internal::checked_args(format_str, args...)); +} +FMT_END_NAMESPACE + +#endif // FMT_CORE_H_ diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/format-inl.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/format-inl.h new file mode 100644 index 0000000..552c943 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/format-inl.h @@ -0,0 +1,972 @@ +// Formatting library for C++ +// +// Copyright (c) 2012 - 2016, Victor Zverovich +// All rights reserved. +// +// For the license information refer to format.h. + +#ifndef FMT_FORMAT_INL_H_ +#define FMT_FORMAT_INL_H_ + +#include "format.h" + +#include + +#include +#include +#include +#include +#include +#include // for std::ptrdiff_t +#include // for std::memmove +#if !defined(FMT_STATIC_THOUSANDS_SEPARATOR) +# include +#endif + +#if FMT_USE_WINDOWS_H +# if !defined(FMT_HEADER_ONLY) && !defined(WIN32_LEAN_AND_MEAN) +# define WIN32_LEAN_AND_MEAN +# endif +# if defined(NOMINMAX) || defined(FMT_WIN_MINMAX) +# include +# else +# define NOMINMAX +# include +# undef NOMINMAX +# endif +#endif + +#if FMT_EXCEPTIONS +# define FMT_TRY try +# define FMT_CATCH(x) catch (x) +#else +# define FMT_TRY if (true) +# define FMT_CATCH(x) if (false) +#endif + +#ifdef _MSC_VER +# pragma warning(push) +# pragma warning(disable: 4127) // conditional expression is constant +# pragma warning(disable: 4702) // unreachable code +// Disable deprecation warning for strerror. The latter is not called but +// MSVC fails to detect it. +# pragma warning(disable: 4996) +#endif + +// Dummy implementations of strerror_r and strerror_s called if corresponding +// system functions are not available. +inline fmt::internal::null<> strerror_r(int, char *, ...) { + return fmt::internal::null<>(); +} +inline fmt::internal::null<> strerror_s(char *, std::size_t, ...) { + return fmt::internal::null<>(); +} + +FMT_BEGIN_NAMESPACE + +namespace { + +#ifndef _MSC_VER +# define FMT_SNPRINTF snprintf +#else // _MSC_VER +inline int fmt_snprintf(char *buffer, size_t size, const char *format, ...) { + va_list args; + va_start(args, format); + int result = vsnprintf_s(buffer, size, _TRUNCATE, format, args); + va_end(args); + return result; +} +# define FMT_SNPRINTF fmt_snprintf +#endif // _MSC_VER + +#if defined(_WIN32) && defined(__MINGW32__) && !defined(__NO_ISOCEXT) +# define FMT_SWPRINTF snwprintf +#else +# define FMT_SWPRINTF swprintf +#endif // defined(_WIN32) && defined(__MINGW32__) && !defined(__NO_ISOCEXT) + +typedef void (*FormatFunc)(internal::buffer &, int, string_view); + +// Portable thread-safe version of strerror. +// Sets buffer to point to a string describing the error code. +// This can be either a pointer to a string stored in buffer, +// or a pointer to some static immutable string. +// Returns one of the following values: +// 0 - success +// ERANGE - buffer is not large enough to store the error message +// other - failure +// Buffer should be at least of size 1. +int safe_strerror( + int error_code, char *&buffer, std::size_t buffer_size) FMT_NOEXCEPT { + FMT_ASSERT(buffer != FMT_NULL && buffer_size != 0, "invalid buffer"); + + class dispatcher { + private: + int error_code_; + char *&buffer_; + std::size_t buffer_size_; + + // A noop assignment operator to avoid bogus warnings. + void operator=(const dispatcher &) {} + + // Handle the result of XSI-compliant version of strerror_r. + int handle(int result) { + // glibc versions before 2.13 return result in errno. + return result == -1 ? errno : result; + } + + // Handle the result of GNU-specific version of strerror_r. + int handle(char *message) { + // If the buffer is full then the message is probably truncated. + if (message == buffer_ && strlen(buffer_) == buffer_size_ - 1) + return ERANGE; + buffer_ = message; + return 0; + } + + // Handle the case when strerror_r is not available. + int handle(internal::null<>) { + return fallback(strerror_s(buffer_, buffer_size_, error_code_)); + } + + // Fallback to strerror_s when strerror_r is not available. + int fallback(int result) { + // If the buffer is full then the message is probably truncated. + return result == 0 && strlen(buffer_) == buffer_size_ - 1 ? + ERANGE : result; + } + +#if !FMT_MSC_VER + // Fallback to strerror if strerror_r and strerror_s are not available. + int fallback(internal::null<>) { + errno = 0; + buffer_ = strerror(error_code_); + return errno; + } +#endif + + public: + dispatcher(int err_code, char *&buf, std::size_t buf_size) + : error_code_(err_code), buffer_(buf), buffer_size_(buf_size) {} + + int run() { + return handle(strerror_r(error_code_, buffer_, buffer_size_)); + } + }; + return dispatcher(error_code, buffer, buffer_size).run(); +} + +void format_error_code(internal::buffer &out, int error_code, + string_view message) FMT_NOEXCEPT { + // Report error code making sure that the output fits into + // inline_buffer_size to avoid dynamic memory allocation and potential + // bad_alloc. + out.resize(0); + static const char SEP[] = ": "; + static const char ERROR_STR[] = "error "; + // Subtract 2 to account for terminating null characters in SEP and ERROR_STR. + std::size_t error_code_size = sizeof(SEP) + sizeof(ERROR_STR) - 2; + typedef internal::int_traits::main_type main_type; + main_type abs_value = static_cast(error_code); + if (internal::is_negative(error_code)) { + abs_value = 0 - abs_value; + ++error_code_size; + } + error_code_size += internal::to_unsigned(internal::count_digits(abs_value)); + writer w(out); + if (message.size() <= inline_buffer_size - error_code_size) { + w.write(message); + w.write(SEP); + } + w.write(ERROR_STR); + w.write(error_code); + assert(out.size() <= inline_buffer_size); +} + +void report_error(FormatFunc func, int error_code, + string_view message) FMT_NOEXCEPT { + memory_buffer full_message; + func(full_message, error_code, message); + // Use Writer::data instead of Writer::c_str to avoid potential memory + // allocation. + std::fwrite(full_message.data(), full_message.size(), 1, stderr); + std::fputc('\n', stderr); +} +} // namespace + +FMT_FUNC size_t internal::count_code_points(basic_string_view s) { + const char8_t *data = s.data(); + size_t num_code_points = 0; + for (size_t i = 0, size = s.size(); i != size; ++i) { + if ((data[i] & 0xc0) != 0x80) + ++num_code_points; + } + return num_code_points; +} + +#if !defined(FMT_STATIC_THOUSANDS_SEPARATOR) +namespace internal { + +template +locale_ref::locale_ref(const Locale &loc) : locale_(&loc) { + static_assert(std::is_same::value, ""); +} + +template +Locale locale_ref::get() const { + static_assert(std::is_same::value, ""); + return locale_ ? *static_cast(locale_) : std::locale(); +} + +template +FMT_FUNC Char thousands_sep_impl(locale_ref loc) { + return std::use_facet >( + loc.get()).thousands_sep(); +} +} +#else +template +FMT_FUNC Char internal::thousands_sep_impl(locale_ref) { + return FMT_STATIC_THOUSANDS_SEPARATOR; +} +#endif + +FMT_FUNC void system_error::init( + int err_code, string_view format_str, format_args args) { + error_code_ = err_code; + memory_buffer buffer; + format_system_error(buffer, err_code, vformat(format_str, args)); + std::runtime_error &base = *this; + base = std::runtime_error(to_string(buffer)); +} + +namespace internal { +template +int char_traits::format_float( + char *buf, std::size_t size, const char *format, int precision, T value) { + return precision < 0 ? + FMT_SNPRINTF(buf, size, format, value) : + FMT_SNPRINTF(buf, size, format, precision, value); +} + +template +int char_traits::format_float( + wchar_t *buf, std::size_t size, const wchar_t *format, int precision, + T value) { + return precision < 0 ? + FMT_SWPRINTF(buf, size, format, value) : + FMT_SWPRINTF(buf, size, format, precision, value); +} + +template +const char basic_data::DIGITS[] = + "0001020304050607080910111213141516171819" + "2021222324252627282930313233343536373839" + "4041424344454647484950515253545556575859" + "6061626364656667686970717273747576777879" + "8081828384858687888990919293949596979899"; + +#define FMT_POWERS_OF_10(factor) \ + factor * 10, \ + factor * 100, \ + factor * 1000, \ + factor * 10000, \ + factor * 100000, \ + factor * 1000000, \ + factor * 10000000, \ + factor * 100000000, \ + factor * 1000000000 + +template +const uint32_t basic_data::POWERS_OF_10_32[] = { + 1, FMT_POWERS_OF_10(1) +}; + +template +const uint32_t basic_data::ZERO_OR_POWERS_OF_10_32[] = { + 0, FMT_POWERS_OF_10(1) +}; + +template +const uint64_t basic_data::ZERO_OR_POWERS_OF_10_64[] = { + 0, + FMT_POWERS_OF_10(1), + FMT_POWERS_OF_10(1000000000ull), + 10000000000000000000ull +}; + +// Normalized 64-bit significands of pow(10, k), for k = -348, -340, ..., 340. +// These are generated by support/compute-powers.py. +template +const uint64_t basic_data::POW10_SIGNIFICANDS[] = { + 0xfa8fd5a0081c0288, 0xbaaee17fa23ebf76, 0x8b16fb203055ac76, + 0xcf42894a5dce35ea, 0x9a6bb0aa55653b2d, 0xe61acf033d1a45df, + 0xab70fe17c79ac6ca, 0xff77b1fcbebcdc4f, 0xbe5691ef416bd60c, + 0x8dd01fad907ffc3c, 0xd3515c2831559a83, 0x9d71ac8fada6c9b5, + 0xea9c227723ee8bcb, 0xaecc49914078536d, 0x823c12795db6ce57, + 0xc21094364dfb5637, 0x9096ea6f3848984f, 0xd77485cb25823ac7, + 0xa086cfcd97bf97f4, 0xef340a98172aace5, 0xb23867fb2a35b28e, + 0x84c8d4dfd2c63f3b, 0xc5dd44271ad3cdba, 0x936b9fcebb25c996, + 0xdbac6c247d62a584, 0xa3ab66580d5fdaf6, 0xf3e2f893dec3f126, + 0xb5b5ada8aaff80b8, 0x87625f056c7c4a8b, 0xc9bcff6034c13053, + 0x964e858c91ba2655, 0xdff9772470297ebd, 0xa6dfbd9fb8e5b88f, + 0xf8a95fcf88747d94, 0xb94470938fa89bcf, 0x8a08f0f8bf0f156b, + 0xcdb02555653131b6, 0x993fe2c6d07b7fac, 0xe45c10c42a2b3b06, + 0xaa242499697392d3, 0xfd87b5f28300ca0e, 0xbce5086492111aeb, + 0x8cbccc096f5088cc, 0xd1b71758e219652c, 0x9c40000000000000, + 0xe8d4a51000000000, 0xad78ebc5ac620000, 0x813f3978f8940984, + 0xc097ce7bc90715b3, 0x8f7e32ce7bea5c70, 0xd5d238a4abe98068, + 0x9f4f2726179a2245, 0xed63a231d4c4fb27, 0xb0de65388cc8ada8, + 0x83c7088e1aab65db, 0xc45d1df942711d9a, 0x924d692ca61be758, + 0xda01ee641a708dea, 0xa26da3999aef774a, 0xf209787bb47d6b85, + 0xb454e4a179dd1877, 0x865b86925b9bc5c2, 0xc83553c5c8965d3d, + 0x952ab45cfa97a0b3, 0xde469fbd99a05fe3, 0xa59bc234db398c25, + 0xf6c69a72a3989f5c, 0xb7dcbf5354e9bece, 0x88fcf317f22241e2, + 0xcc20ce9bd35c78a5, 0x98165af37b2153df, 0xe2a0b5dc971f303a, + 0xa8d9d1535ce3b396, 0xfb9b7cd9a4a7443c, 0xbb764c4ca7a44410, + 0x8bab8eefb6409c1a, 0xd01fef10a657842c, 0x9b10a4e5e9913129, + 0xe7109bfba19c0c9d, 0xac2820d9623bf429, 0x80444b5e7aa7cf85, + 0xbf21e44003acdd2d, 0x8e679c2f5e44ff8f, 0xd433179d9c8cb841, + 0x9e19db92b4e31ba9, 0xeb96bf6ebadf77d9, 0xaf87023b9bf0ee6b, +}; + +// Binary exponents of pow(10, k), for k = -348, -340, ..., 340, corresponding +// to significands above. +template +const int16_t basic_data::POW10_EXPONENTS[] = { + -1220, -1193, -1166, -1140, -1113, -1087, -1060, -1034, -1007, -980, -954, + -927, -901, -874, -847, -821, -794, -768, -741, -715, -688, -661, + -635, -608, -582, -555, -529, -502, -475, -449, -422, -396, -369, + -343, -316, -289, -263, -236, -210, -183, -157, -130, -103, -77, + -50, -24, 3, 30, 56, 83, 109, 136, 162, 189, 216, + 242, 269, 295, 322, 348, 375, 402, 428, 455, 481, 508, + 534, 561, 588, 614, 641, 667, 694, 720, 747, 774, 800, + 827, 853, 880, 907, 933, 960, 986, 1013, 1039, 1066 +}; + +template const char basic_data::FOREGROUND_COLOR[] = "\x1b[38;2;"; +template const char basic_data::BACKGROUND_COLOR[] = "\x1b[48;2;"; +template const char basic_data::RESET_COLOR[] = "\x1b[0m"; +template const wchar_t basic_data::WRESET_COLOR[] = L"\x1b[0m"; + +// A handmade floating-point number f * pow(2, e). +class fp { + private: + typedef uint64_t significand_type; + + // All sizes are in bits. + static FMT_CONSTEXPR_DECL const int char_size = + std::numeric_limits::digits; + // Subtract 1 to account for an implicit most significant bit in the + // normalized form. + static FMT_CONSTEXPR_DECL const int double_significand_size = + std::numeric_limits::digits - 1; + static FMT_CONSTEXPR_DECL const uint64_t implicit_bit = + 1ull << double_significand_size; + + public: + significand_type f; + int e; + + static FMT_CONSTEXPR_DECL const int significand_size = + sizeof(significand_type) * char_size; + + fp(): f(0), e(0) {} + fp(uint64_t f_val, int e_val): f(f_val), e(e_val) {} + + // Constructs fp from an IEEE754 double. It is a template to prevent compile + // errors on platforms where double is not IEEE754. + template + explicit fp(Double d) { + // Assume double is in the format [sign][exponent][significand]. + typedef std::numeric_limits limits; + const int double_size = static_cast(sizeof(Double) * char_size); + const int exponent_size = + double_size - double_significand_size - 1; // -1 for sign + const uint64_t significand_mask = implicit_bit - 1; + const uint64_t exponent_mask = (~0ull >> 1) & ~significand_mask; + const int exponent_bias = (1 << exponent_size) - limits::max_exponent - 1; + auto u = bit_cast(d); + auto biased_e = (u & exponent_mask) >> double_significand_size; + f = u & significand_mask; + if (biased_e != 0) + f += implicit_bit; + else + biased_e = 1; // Subnormals use biased exponent 1 (min exponent). + e = static_cast(biased_e - exponent_bias - double_significand_size); + } + + // Normalizes the value converted from double and multiplied by (1 << SHIFT). + template + void normalize() { + // Handle subnormals. + auto shifted_implicit_bit = implicit_bit << SHIFT; + while ((f & shifted_implicit_bit) == 0) { + f <<= 1; + --e; + } + // Subtract 1 to account for hidden bit. + auto offset = significand_size - double_significand_size - SHIFT - 1; + f <<= offset; + e -= offset; + } + + // Compute lower and upper boundaries (m^- and m^+ in the Grisu paper), where + // a boundary is a value half way between the number and its predecessor + // (lower) or successor (upper). The upper boundary is normalized and lower + // has the same exponent but may be not normalized. + void compute_boundaries(fp &lower, fp &upper) const { + lower = f == implicit_bit ? + fp((f << 2) - 1, e - 2) : fp((f << 1) - 1, e - 1); + upper = fp((f << 1) + 1, e - 1); + upper.normalize<1>(); // 1 is to account for the exponent shift above. + lower.f <<= lower.e - upper.e; + lower.e = upper.e; + } +}; + +// Returns an fp number representing x - y. Result may not be normalized. +inline fp operator-(fp x, fp y) { + FMT_ASSERT(x.f >= y.f && x.e == y.e, "invalid operands"); + return fp(x.f - y.f, x.e); +} + +// Computes an fp number r with r.f = x.f * y.f / pow(2, 64) rounded to nearest +// with half-up tie breaking, r.e = x.e + y.e + 64. Result may not be normalized. +FMT_API fp operator*(fp x, fp y); + +// Returns cached power (of 10) c_k = c_k.f * pow(2, c_k.e) such that its +// (binary) exponent satisfies min_exponent <= c_k.e <= min_exponent + 3. +FMT_API fp get_cached_power(int min_exponent, int &pow10_exponent); + +FMT_FUNC fp operator*(fp x, fp y) { + // Multiply 32-bit parts of significands. + uint64_t mask = (1ULL << 32) - 1; + uint64_t a = x.f >> 32, b = x.f & mask; + uint64_t c = y.f >> 32, d = y.f & mask; + uint64_t ac = a * c, bc = b * c, ad = a * d, bd = b * d; + // Compute mid 64-bit of result and round. + uint64_t mid = (bd >> 32) + (ad & mask) + (bc & mask) + (1U << 31); + return fp(ac + (ad >> 32) + (bc >> 32) + (mid >> 32), x.e + y.e + 64); +} + +FMT_FUNC fp get_cached_power(int min_exponent, int &pow10_exponent) { + const double one_over_log2_10 = 0.30102999566398114; // 1 / log2(10) + int index = static_cast(std::ceil( + (min_exponent + fp::significand_size - 1) * one_over_log2_10)); + // Decimal exponent of the first (smallest) cached power of 10. + const int first_dec_exp = -348; + // Difference between 2 consecutive decimal exponents in cached powers of 10. + const int dec_exp_step = 8; + index = (index - first_dec_exp - 1) / dec_exp_step + 1; + pow10_exponent = first_dec_exp + index * dec_exp_step; + return fp(data::POW10_SIGNIFICANDS[index], data::POW10_EXPONENTS[index]); +} + +FMT_FUNC bool grisu2_round( + char *buf, int &size, int max_digits, uint64_t delta, + uint64_t remainder, uint64_t exp, uint64_t diff, int &exp10) { + while (remainder < diff && delta - remainder >= exp && + (remainder + exp < diff || diff - remainder > remainder + exp - diff)) { + --buf[size - 1]; + remainder += exp; + } + if (size > max_digits) { + --size; + ++exp10; + if (buf[size] >= '5') + return false; + } + return true; +} + +// Generates output using Grisu2 digit-gen algorithm. +FMT_FUNC bool grisu2_gen_digits( + char *buf, int &size, uint32_t hi, uint64_t lo, int &exp, + uint64_t delta, const fp &one, const fp &diff, int max_digits) { + // Generate digits for the most significant part (hi). + while (exp > 0) { + uint32_t digit = 0; + // This optimization by miloyip reduces the number of integer divisions by + // one per iteration. + switch (exp) { + case 10: digit = hi / 1000000000; hi %= 1000000000; break; + case 9: digit = hi / 100000000; hi %= 100000000; break; + case 8: digit = hi / 10000000; hi %= 10000000; break; + case 7: digit = hi / 1000000; hi %= 1000000; break; + case 6: digit = hi / 100000; hi %= 100000; break; + case 5: digit = hi / 10000; hi %= 10000; break; + case 4: digit = hi / 1000; hi %= 1000; break; + case 3: digit = hi / 100; hi %= 100; break; + case 2: digit = hi / 10; hi %= 10; break; + case 1: digit = hi; hi = 0; break; + default: + FMT_ASSERT(false, "invalid number of digits"); + } + if (digit != 0 || size != 0) + buf[size++] = static_cast('0' + digit); + --exp; + uint64_t remainder = (static_cast(hi) << -one.e) + lo; + if (remainder <= delta || size > max_digits) { + return grisu2_round( + buf, size, max_digits, delta, remainder, + static_cast(data::POWERS_OF_10_32[exp]) << -one.e, + diff.f, exp); + } + } + // Generate digits for the least significant part (lo). + for (;;) { + lo *= 10; + delta *= 10; + char digit = static_cast(lo >> -one.e); + if (digit != 0 || size != 0) + buf[size++] = static_cast('0' + digit); + lo &= one.f - 1; + --exp; + if (lo < delta || size > max_digits) { + return grisu2_round(buf, size, max_digits, delta, lo, one.f, + diff.f * data::POWERS_OF_10_32[-exp], exp); + } + } +} + +#if FMT_CLANG_VERSION +# define FMT_FALLTHROUGH [[clang::fallthrough]]; +#elif FMT_GCC_VERSION >= 700 +# define FMT_FALLTHROUGH [[gnu::fallthrough]]; +#else +# define FMT_FALLTHROUGH +#endif + +struct gen_digits_params { + int num_digits; + bool fixed; + bool upper; + bool trailing_zeros; +}; + +struct prettify_handler { + char *data; + ptrdiff_t size; + buffer &buf; + + explicit prettify_handler(buffer &b, ptrdiff_t n) + : data(b.data()), size(n), buf(b) {} + ~prettify_handler() { + assert(buf.size() >= to_unsigned(size)); + buf.resize(to_unsigned(size)); + } + + template + void insert(ptrdiff_t pos, ptrdiff_t n, F f) { + std::memmove(data + pos + n, data + pos, to_unsigned(size - pos)); + f(data + pos); + size += n; + } + + void insert(ptrdiff_t pos, char c) { + std::memmove(data + pos + 1, data + pos, to_unsigned(size - pos)); + data[pos] = c; + ++size; + } + + void append(ptrdiff_t n, char c) { + std::uninitialized_fill_n(data + size, n, c); + size += n; + } + + void append(char c) { data[size++] = c; } + + void remove_trailing(char c) { + while (data[size - 1] == c) --size; + } +}; + +// Writes the exponent exp in the form "[+-]d{2,3}" to buffer. +template +FMT_FUNC void write_exponent(int exp, Handler &&h) { + FMT_ASSERT(-1000 < exp && exp < 1000, "exponent out of range"); + if (exp < 0) { + h.append('-'); + exp = -exp; + } else { + h.append('+'); + } + if (exp >= 100) { + h.append(static_cast('0' + exp / 100)); + exp %= 100; + const char *d = data::DIGITS + exp * 2; + h.append(d[0]); + h.append(d[1]); + } else { + const char *d = data::DIGITS + exp * 2; + h.append(d[0]); + h.append(d[1]); + } +} + +struct fill { + size_t n; + void operator()(char *buf) const { + buf[0] = '0'; + buf[1] = '.'; + std::uninitialized_fill_n(buf + 2, n, '0'); + } +}; + +// The number is given as v = f * pow(10, exp), where f has size digits. +template +FMT_FUNC void grisu2_prettify(const gen_digits_params ¶ms, + int size, int exp, Handler &&handler) { + if (!params.fixed) { + // Insert a decimal point after the first digit and add an exponent. + handler.insert(1, '.'); + exp += size - 1; + if (size < params.num_digits) + handler.append(params.num_digits - size, '0'); + handler.append(params.upper ? 'E' : 'e'); + write_exponent(exp, handler); + return; + } + // pow(10, full_exp - 1) <= v <= pow(10, full_exp). + int full_exp = size + exp; + const int exp_threshold = 21; + if (size <= full_exp && full_exp <= exp_threshold) { + // 1234e7 -> 12340000000[.0+] + handler.append(full_exp - size, '0'); + int num_zeros = params.num_digits - full_exp; + if (num_zeros > 0 && params.trailing_zeros) { + handler.append('.'); + handler.append(num_zeros, '0'); + } + } else if (full_exp > 0) { + // 1234e-2 -> 12.34[0+] + handler.insert(full_exp, '.'); + if (!params.trailing_zeros) { + // Remove trailing zeros. + handler.remove_trailing('0'); + } else if (params.num_digits > size) { + // Add trailing zeros. + ptrdiff_t num_zeros = params.num_digits - size; + handler.append(num_zeros, '0'); + } + } else { + // 1234e-6 -> 0.001234 + handler.insert(0, 2 - full_exp, fill{to_unsigned(-full_exp)}); + } +} + +struct char_counter { + ptrdiff_t size; + + template + void insert(ptrdiff_t, ptrdiff_t n, F) { size += n; } + void insert(ptrdiff_t, char) { ++size; } + void append(ptrdiff_t n, char) { size += n; } + void append(char) { ++size; } + void remove_trailing(char) {} +}; + +// Converts format specifiers into parameters for digit generation and computes +// output buffer size for a number in the range [pow(10, exp - 1), pow(10, exp) +// or 0 if exp == 1. +FMT_FUNC gen_digits_params process_specs(const core_format_specs &specs, + int exp, buffer &buf) { + auto params = gen_digits_params(); + int num_digits = specs.precision >= 0 ? specs.precision : 6; + switch (specs.type) { + case 'G': + params.upper = true; + FMT_FALLTHROUGH + case '\0': case 'g': + params.trailing_zeros = (specs.flags & HASH_FLAG) != 0; + if (-4 <= exp && exp < num_digits + 1) { + params.fixed = true; + if (!specs.type && params.trailing_zeros && exp >= 0) + num_digits = exp + 1; + } + break; + case 'F': + params.upper = true; + FMT_FALLTHROUGH + case 'f': { + params.fixed = true; + params.trailing_zeros = true; + int adjusted_min_digits = num_digits + exp; + if (adjusted_min_digits > 0) + num_digits = adjusted_min_digits; + break; + } + case 'E': + params.upper = true; + FMT_FALLTHROUGH + case 'e': + ++num_digits; + break; + } + params.num_digits = num_digits; + char_counter counter{num_digits}; + grisu2_prettify(params, params.num_digits, exp - num_digits, counter); + buf.resize(to_unsigned(counter.size)); + return params; +} + +template +FMT_FUNC typename std::enable_if::type + grisu2_format(Double value, buffer &buf, core_format_specs specs) { + FMT_ASSERT(value >= 0, "value is negative"); + if (value == 0) { + gen_digits_params params = process_specs(specs, 1, buf); + const size_t size = 1; + buf[0] = '0'; + grisu2_prettify(params, size, 0, prettify_handler(buf, size)); + return true; + } + + fp fp_value(value); + fp lower, upper; // w^- and w^+ in the Grisu paper. + fp_value.compute_boundaries(lower, upper); + + // Find a cached power of 10 close to 1 / upper and use it to scale upper. + const int min_exp = -60; // alpha in Grisu. + int cached_exp = 0; // K in Grisu. + auto cached_pow = get_cached_power( // \tilde{c}_{-k} in Grisu. + min_exp - (upper.e + fp::significand_size), cached_exp); + cached_exp = -cached_exp; + upper = upper * cached_pow; // \tilde{M}^+ in Grisu. + --upper.f; // \tilde{M}^+ - 1 ulp -> M^+_{\downarrow}. + fp one(1ull << -upper.e, upper.e); + // hi (p1 in Grisu) contains the most significant digits of scaled_upper. + // hi = floor(upper / one). + uint32_t hi = static_cast(upper.f >> -one.e); + int exp = count_digits(hi); // kappa in Grisu. + gen_digits_params params = process_specs(specs, cached_exp + exp, buf); + fp_value.normalize(); + fp scaled_value = fp_value * cached_pow; + lower = lower * cached_pow; // \tilde{M}^- in Grisu. + ++lower.f; // \tilde{M}^- + 1 ulp -> M^-_{\uparrow}. + uint64_t delta = upper.f - lower.f; + fp diff = upper - scaled_value; // wp_w in Grisu. + // lo (p2 in Grisu) contains the least significants digits of scaled_upper. + // lo = supper % one. + uint64_t lo = upper.f & (one.f - 1); + int size = 0; + if (!grisu2_gen_digits(buf.data(), size, hi, lo, exp, delta, one, diff, + params.num_digits)) { + buf.clear(); + return false; + } + grisu2_prettify(params, size, cached_exp + exp, prettify_handler(buf, size)); + return true; +} + +template +void sprintf_format(Double value, internal::buffer &buf, + core_format_specs spec) { + // Buffer capacity must be non-zero, otherwise MSVC's vsnprintf_s will fail. + FMT_ASSERT(buf.capacity() != 0, "empty buffer"); + + // Build format string. + enum { MAX_FORMAT_SIZE = 10}; // longest format: %#-*.*Lg + char format[MAX_FORMAT_SIZE]; + char *format_ptr = format; + *format_ptr++ = '%'; + if (spec.has(HASH_FLAG)) + *format_ptr++ = '#'; + if (spec.precision >= 0) { + *format_ptr++ = '.'; + *format_ptr++ = '*'; + } + if (std::is_same::value) + *format_ptr++ = 'L'; + *format_ptr++ = spec.type; + *format_ptr = '\0'; + + // Format using snprintf. + char *start = FMT_NULL; + for (;;) { + std::size_t buffer_size = buf.capacity(); + start = &buf[0]; + int result = internal::char_traits::format_float( + start, buffer_size, format, spec.precision, value); + if (result >= 0) { + unsigned n = internal::to_unsigned(result); + if (n < buf.capacity()) { + buf.resize(n); + break; // The buffer is large enough - continue with formatting. + } + buf.reserve(n + 1); + } else { + // If result is negative we ask to increase the capacity by at least 1, + // but as std::vector, the buffer grows exponentially. + buf.reserve(buf.capacity() + 1); + } + } +} +} // namespace internal + +#if FMT_USE_WINDOWS_H + +FMT_FUNC internal::utf8_to_utf16::utf8_to_utf16(string_view s) { + static const char ERROR_MSG[] = "cannot convert string from UTF-8 to UTF-16"; + if (s.size() > INT_MAX) + FMT_THROW(windows_error(ERROR_INVALID_PARAMETER, ERROR_MSG)); + int s_size = static_cast(s.size()); + if (s_size == 0) { + // MultiByteToWideChar does not support zero length, handle separately. + buffer_.resize(1); + buffer_[0] = 0; + return; + } + + int length = MultiByteToWideChar( + CP_UTF8, MB_ERR_INVALID_CHARS, s.data(), s_size, FMT_NULL, 0); + if (length == 0) + FMT_THROW(windows_error(GetLastError(), ERROR_MSG)); + buffer_.resize(length + 1); + length = MultiByteToWideChar( + CP_UTF8, MB_ERR_INVALID_CHARS, s.data(), s_size, &buffer_[0], length); + if (length == 0) + FMT_THROW(windows_error(GetLastError(), ERROR_MSG)); + buffer_[length] = 0; +} + +FMT_FUNC internal::utf16_to_utf8::utf16_to_utf8(wstring_view s) { + if (int error_code = convert(s)) { + FMT_THROW(windows_error(error_code, + "cannot convert string from UTF-16 to UTF-8")); + } +} + +FMT_FUNC int internal::utf16_to_utf8::convert(wstring_view s) { + if (s.size() > INT_MAX) + return ERROR_INVALID_PARAMETER; + int s_size = static_cast(s.size()); + if (s_size == 0) { + // WideCharToMultiByte does not support zero length, handle separately. + buffer_.resize(1); + buffer_[0] = 0; + return 0; + } + + int length = WideCharToMultiByte( + CP_UTF8, 0, s.data(), s_size, FMT_NULL, 0, FMT_NULL, FMT_NULL); + if (length == 0) + return GetLastError(); + buffer_.resize(length + 1); + length = WideCharToMultiByte( + CP_UTF8, 0, s.data(), s_size, &buffer_[0], length, FMT_NULL, FMT_NULL); + if (length == 0) + return GetLastError(); + buffer_[length] = 0; + return 0; +} + +FMT_FUNC void windows_error::init( + int err_code, string_view format_str, format_args args) { + error_code_ = err_code; + memory_buffer buffer; + internal::format_windows_error(buffer, err_code, vformat(format_str, args)); + std::runtime_error &base = *this; + base = std::runtime_error(to_string(buffer)); +} + +FMT_FUNC void internal::format_windows_error( + internal::buffer &out, int error_code, string_view message) FMT_NOEXCEPT { + FMT_TRY { + wmemory_buffer buf; + buf.resize(inline_buffer_size); + for (;;) { + wchar_t *system_message = &buf[0]; + int result = FormatMessageW( + FORMAT_MESSAGE_FROM_SYSTEM | FORMAT_MESSAGE_IGNORE_INSERTS, + FMT_NULL, error_code, MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT), + system_message, static_cast(buf.size()), FMT_NULL); + if (result != 0) { + utf16_to_utf8 utf8_message; + if (utf8_message.convert(system_message) == ERROR_SUCCESS) { + writer w(out); + w.write(message); + w.write(": "); + w.write(utf8_message); + return; + } + break; + } + if (GetLastError() != ERROR_INSUFFICIENT_BUFFER) + break; // Can't get error message, report error code instead. + buf.resize(buf.size() * 2); + } + } FMT_CATCH(...) {} + format_error_code(out, error_code, message); +} + +#endif // FMT_USE_WINDOWS_H + +FMT_FUNC void format_system_error( + internal::buffer &out, int error_code, string_view message) FMT_NOEXCEPT { + FMT_TRY { + memory_buffer buf; + buf.resize(inline_buffer_size); + for (;;) { + char *system_message = &buf[0]; + int result = safe_strerror(error_code, system_message, buf.size()); + if (result == 0) { + writer w(out); + w.write(message); + w.write(": "); + w.write(system_message); + return; + } + if (result != ERANGE) + break; // Can't get error message, report error code instead. + buf.resize(buf.size() * 2); + } + } FMT_CATCH(...) {} + format_error_code(out, error_code, message); +} + +FMT_FUNC void internal::error_handler::on_error(const char *message) { + FMT_THROW(format_error(message)); +} + +FMT_FUNC void report_system_error( + int error_code, fmt::string_view message) FMT_NOEXCEPT { + report_error(format_system_error, error_code, message); +} + +#if FMT_USE_WINDOWS_H +FMT_FUNC void report_windows_error( + int error_code, fmt::string_view message) FMT_NOEXCEPT { + report_error(internal::format_windows_error, error_code, message); +} +#endif + +FMT_FUNC void vprint(std::FILE *f, string_view format_str, format_args args) { + memory_buffer buffer; + internal::vformat_to(buffer, format_str, + basic_format_args::type>(args)); + std::fwrite(buffer.data(), 1, buffer.size(), f); +} + +FMT_FUNC void vprint(std::FILE *f, wstring_view format_str, wformat_args args) { + wmemory_buffer buffer; + internal::vformat_to(buffer, format_str, args); + std::fwrite(buffer.data(), sizeof(wchar_t), buffer.size(), f); +} + +FMT_FUNC void vprint(string_view format_str, format_args args) { + vprint(stdout, format_str, args); +} + +FMT_FUNC void vprint(wstring_view format_str, wformat_args args) { + vprint(stdout, format_str, args); +} + +FMT_END_NAMESPACE + +#ifdef _MSC_VER +# pragma warning(pop) +#endif + +#endif // FMT_FORMAT_INL_H_ diff --git a/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/format.h b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/format.h new file mode 100644 index 0000000..1bb24a5 --- /dev/null +++ b/lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/format.h @@ -0,0 +1,3555 @@ +/* + Formatting library for C++ + + Copyright (c) 2012 - present, Victor Zverovich + All rights reserved. + + Redistribution and use in source and binary forms, with or without + modification, are permitted provided that the following conditions are met: + + 1. Redistributions of source code must retain the above copyright notice, this + list of conditions and the following disclaimer. + 2. Redistributions in binary form must reproduce the above copyright notice, + this list of conditions and the following disclaimer in the documentation + and/or other materials provided with the distribution. + + THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND + ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED + WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE + DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR + ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES + (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; + LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND + ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT + (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS + SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. + */ + +#ifndef FMT_FORMAT_H_ +#define FMT_FORMAT_H_ + +#include +#include +#include +#include +#include +#include +#include +#include + +#ifdef __clang__ +# define FMT_CLANG_VERSION (__clang_major__ * 100 + __clang_minor__) +#else +# define FMT_CLANG_VERSION 0 +#endif + +#ifdef __INTEL_COMPILER +# define FMT_ICC_VERSION __INTEL_COMPILER +#elif defined(__ICL) +# define FMT_ICC_VERSION __ICL +#else +# define FMT_ICC_VERSION 0 +#endif + +#ifdef __NVCC__ +# define FMT_CUDA_VERSION (__CUDACC_VER_MAJOR__ * 100 + __CUDACC_VER_MINOR__) +#else +# define FMT_CUDA_VERSION 0 +#endif + +#include "core.h" + +#if FMT_GCC_VERSION >= 406 || FMT_CLANG_VERSION +# pragma GCC diagnostic push + +// Disable the warning about declaration shadowing because it affects too +// many valid cases. +# pragma GCC diagnostic ignored "-Wshadow" + +// Disable the warning about nonliteral format strings because we construct +// them dynamically when falling back to snprintf for FP formatting. +# pragma GCC diagnostic ignored "-Wformat-nonliteral" +#endif + +# if FMT_CLANG_VERSION +# pragma GCC diagnostic ignored "-Wgnu-string-literal-operator-template" +# endif + +#ifdef _SECURE_SCL +# define FMT_SECURE_SCL _SECURE_SCL +#else +# define FMT_SECURE_SCL 0 +#endif + +#if FMT_SECURE_SCL +# include +#endif + +#ifdef __has_builtin +# define FMT_HAS_BUILTIN(x) __has_builtin(x) +#else +# define FMT_HAS_BUILTIN(x) 0 +#endif + +#ifdef __GNUC_LIBSTD__ +# define FMT_GNUC_LIBSTD_VERSION (__GNUC_LIBSTD__ * 100 + __GNUC_LIBSTD_MINOR__) +#endif + +#ifndef FMT_THROW +# if FMT_EXCEPTIONS +# if FMT_MSC_VER +FMT_BEGIN_NAMESPACE +namespace internal { +template +inline void do_throw(const Exception &x) { + // Silence unreachable code warnings in MSVC because these are nearly + // impossible to fix in a generic code. + volatile bool b = true; + if (b) + throw x; +} +} +FMT_END_NAMESPACE +# define FMT_THROW(x) fmt::internal::do_throw(x) +# else +# define FMT_THROW(x) throw x +# endif +# else +# define FMT_THROW(x) do { static_cast(sizeof(x)); assert(false); } while(false); +# endif +#endif + +#ifndef FMT_USE_USER_DEFINED_LITERALS +// For Intel's compiler and NVIDIA's compiler both it and the system gcc/msc +// must support UDLs. +# if (FMT_HAS_FEATURE(cxx_user_literals) || \ + FMT_GCC_VERSION >= 407 || FMT_MSC_VER >= 1900) && \ + (!(FMT_ICC_VERSION || FMT_CUDA_VERSION) || \ + FMT_ICC_VERSION >= 1500 || FMT_CUDA_VERSION >= 700) +# define FMT_USE_USER_DEFINED_LITERALS 1 +# else +# define FMT_USE_USER_DEFINED_LITERALS 0 +# endif +#endif + +// EDG C++ Front End based compilers (icc, nvcc) do not currently support UDL +// templates. +#if FMT_USE_USER_DEFINED_LITERALS && \ + FMT_ICC_VERSION == 0 && \ + FMT_CUDA_VERSION == 0 && \ + ((FMT_GCC_VERSION >= 600 && __cplusplus >= 201402L) || \ + (defined(FMT_CLANG_VERSION) && FMT_CLANG_VERSION >= 304)) +# define FMT_UDL_TEMPLATE 1 +#else +# define FMT_UDL_TEMPLATE 0 +#endif + +#ifndef FMT_USE_EXTERN_TEMPLATES +# ifndef FMT_HEADER_ONLY +# define FMT_USE_EXTERN_TEMPLATES \ + ((FMT_CLANG_VERSION >= 209 && __cplusplus >= 201103L) || \ + (FMT_GCC_VERSION >= 303 && FMT_HAS_GXX_CXX11)) +# else +# define FMT_USE_EXTERN_TEMPLATES 0 +# endif +#endif + +#if FMT_HAS_GXX_CXX11 || FMT_HAS_FEATURE(cxx_trailing_return) || \ + FMT_MSC_VER >= 1600 +# define FMT_USE_TRAILING_RETURN 1 +#else +# define FMT_USE_TRAILING_RETURN 0 +#endif + +#ifndef FMT_USE_GRISU +# define FMT_USE_GRISU 0 +//# define FMT_USE_GRISU std::numeric_limits::is_iec559 +#endif + +// __builtin_clz is broken in clang with Microsoft CodeGen: +// https://github.com/fmtlib/fmt/issues/519 +#ifndef _MSC_VER +# if FMT_GCC_VERSION >= 400 || FMT_HAS_BUILTIN(__builtin_clz) +# define FMT_BUILTIN_CLZ(n) __builtin_clz(n) +# endif + +# if FMT_GCC_VERSION >= 400 || FMT_HAS_BUILTIN(__builtin_clzll) +# define FMT_BUILTIN_CLZLL(n) __builtin_clzll(n) +# endif +#endif + +// Some compilers masquerade as both MSVC and GCC-likes or otherwise support +// __builtin_clz and __builtin_clzll, so only define FMT_BUILTIN_CLZ using the +// MSVC intrinsics if the clz and clzll builtins are not available. +#if FMT_MSC_VER && !defined(FMT_BUILTIN_CLZLL) && !defined(_MANAGED) +# include // _BitScanReverse, _BitScanReverse64 + +FMT_BEGIN_NAMESPACE +namespace internal { +// Avoid Clang with Microsoft CodeGen's -Wunknown-pragmas warning. +# ifndef __clang__ +# pragma intrinsic(_BitScanReverse) +# endif +inline uint32_t clz(uint32_t x) { + unsigned long r = 0; + _BitScanReverse(&r, x); + + assert(x != 0); + // Static analysis complains about using uninitialized data + // "r", but the only way that can happen is if "x" is 0, + // which the callers guarantee to not happen. +# pragma warning(suppress: 6102) + return 31 - r; +} +# define FMT_BUILTIN_CLZ(n) fmt::internal::clz(n) + +# if defined(_WIN64) && !defined(__clang__) +# pragma intrinsic(_BitScanReverse64) +# endif + +inline uint32_t clzll(uint64_t x) { + unsigned long r = 0; +# ifdef _WIN64 + _BitScanReverse64(&r, x); +# else + // Scan the high 32 bits. + if (_BitScanReverse(&r, static_cast(x >> 32))) + return 63 - (r + 32); + + // Scan the low 32 bits. + _BitScanReverse(&r, static_cast(x)); +# endif + + assert(x != 0); + // Static analysis complains about using uninitialized data + // "r", but the only way that can happen is if "x" is 0, + // which the callers guarantee to not happen. +# pragma warning(suppress: 6102) + return 63 - r; +} +# define FMT_BUILTIN_CLZLL(n) fmt::internal::clzll(n) +} +FMT_END_NAMESPACE +#endif + +FMT_BEGIN_NAMESPACE +namespace internal { + +// An equivalent of `*reinterpret_cast(&source)` that doesn't produce +// undefined behavior (e.g. due to type aliasing). +// Example: uint64_t d = bit_cast(2.718); +template +inline Dest bit_cast(const Source& source) { + static_assert(sizeof(Dest) == sizeof(Source), "size mismatch"); + Dest dest; + std::memcpy(&dest, &source, sizeof(dest)); + return dest; +} + +// An implementation of begin and end for pre-C++11 compilers such as gcc 4. +template +FMT_CONSTEXPR auto begin(const C &c) -> decltype(c.begin()) { + return c.begin(); +} +template +FMT_CONSTEXPR T *begin(T (&array)[N]) FMT_NOEXCEPT { return array; } +template +FMT_CONSTEXPR auto end(const C &c) -> decltype(c.end()) { return c.end(); } +template +FMT_CONSTEXPR T *end(T (&array)[N]) FMT_NOEXCEPT { return array + N; } + +// For std::result_of in gcc 4.4. +template +struct function { + template + struct result { typedef Result type; }; +}; + +struct dummy_int { + int data[2]; + operator int() const { return 0; } +}; +typedef std::numeric_limits fputil; + +// Dummy implementations of system functions called if the latter are not +// available. +inline dummy_int isinf(...) { return dummy_int(); } +inline dummy_int _finite(...) { return dummy_int(); } +inline dummy_int isnan(...) { return dummy_int(); } +inline dummy_int _isnan(...) { return dummy_int(); } + +template +typename Allocator::value_type *allocate(Allocator& alloc, std::size_t n) { +#if __cplusplus >= 201103L || FMT_MSC_VER >= 1700 + return std::allocator_traits::allocate(alloc, n); +#else + return alloc.allocate(n); +#endif +} + +// A helper function to suppress bogus "conditional expression is constant" +// warnings. +template +inline T const_check(T value) { return value; } +} // namespace internal +FMT_END_NAMESPACE + +namespace std { +// Standard permits specialization of std::numeric_limits. This specialization +// is used to resolve ambiguity between isinf and std::isinf in glibc: +// https://gcc.gnu.org/bugzilla/show_bug.cgi?id=48891 +// and the same for isnan. +template <> +class numeric_limits : + public std::numeric_limits { + public: + // Portable version of isinf. + template + static bool isinfinity(T x) { + using namespace fmt::internal; + // The resolution "priority" is: + // isinf macro > std::isinf > ::isinf > fmt::internal::isinf + if (const_check(sizeof(isinf(x)) != sizeof(fmt::internal::dummy_int))) + return isinf(x) != 0; + return !_finite(static_cast(x)); + } + + // Portable version of isnan. + template + static bool isnotanumber(T x) { + using namespace fmt::internal; + if (const_check(sizeof(isnan(x)) != sizeof(fmt::internal::dummy_int))) + return isnan(x) != 0; + return _isnan(static_cast(x)) != 0; + } +}; +} // namespace std + +FMT_BEGIN_NAMESPACE +template +class basic_writer; + +template +class output_range { + private: + OutputIt it_; + + // Unused yet. + typedef void sentinel; + sentinel end() const; + + public: + typedef OutputIt iterator; + typedef T value_type; + + explicit output_range(OutputIt it): it_(it) {} + OutputIt begin() const { return it_; } +}; + +// A range where begin() returns back_insert_iterator. +template +class back_insert_range: + public output_range> { + typedef output_range> base; + public: + typedef typename Container::value_type value_type; + + back_insert_range(Container &c): base(std::back_inserter(c)) {} + back_insert_range(typename base::iterator it): base(it) {} +}; + +typedef basic_writer> writer; +typedef basic_writer> wwriter; + +/** A formatting error such as invalid format string. */ +class format_error : public std::runtime_error { + public: + explicit format_error(const char *message) + : std::runtime_error(message) {} + + explicit format_error(const std::string &message) + : std::runtime_error(message) {} +}; + +namespace internal { + +#if FMT_SECURE_SCL +template +struct checked { typedef stdext::checked_array_iterator type; }; + +// Make a checked iterator to avoid warnings on MSVC. +template +inline stdext::checked_array_iterator make_checked(T *p, std::size_t size) { + return {p, size}; +} +#else +template +struct checked { typedef T *type; }; +template +inline T *make_checked(T *p, std::size_t) { return p; } +#endif + +template +template +void basic_buffer::append(const U *begin, const U *end) { + std::size_t new_size = size_ + internal::to_unsigned(end - begin); + reserve(new_size); + std::uninitialized_copy(begin, end, + internal::make_checked(ptr_, capacity_) + size_); + size_ = new_size; +} +} // namespace internal + +// C++20 feature test, since r346892 Clang considers char8_t a fundamental +// type in this mode. If this is the case __cpp_char8_t will be defined. +#if !defined(__cpp_char8_t) +// A UTF-8 code unit type. +enum char8_t: unsigned char {}; +#endif + +// A UTF-8 string view. +class u8string_view : public basic_string_view { + public: + typedef char8_t char_type; + + u8string_view(const char *s): + basic_string_view(reinterpret_cast(s)) {} + u8string_view(const char *s, size_t count) FMT_NOEXCEPT: + basic_string_view(reinterpret_cast(s), count) {} +}; + +#if FMT_USE_USER_DEFINED_LITERALS +inline namespace literals { +inline u8string_view operator"" _u(const char *s, std::size_t n) { + return {s, n}; +} +} +#endif + +// The number of characters to store in the basic_memory_buffer object itself +// to avoid dynamic memory allocation. +enum { inline_buffer_size = 500 }; + +/** + \rst + A dynamically growing memory buffer for trivially copyable/constructible types + with the first ``SIZE`` elements stored in the object itself. + + You can use one of the following typedefs for common character types: + + +----------------+------------------------------+ + | Type | Definition | + +================+==============================+ + | memory_buffer | basic_memory_buffer | + +----------------+------------------------------+ + | wmemory_buffer | basic_memory_buffer | + +----------------+------------------------------+ + + **Example**:: + + fmt::memory_buffer out; + format_to(out, "The answer is {}.", 42); + + This will append the following output to the ``out`` object: + + .. code-block:: none + + The answer is 42. + + The output can be converted to an ``std::string`` with ``to_string(out)``. + \endrst + */ +template > +class basic_memory_buffer: private Allocator, public internal::basic_buffer { + private: + T store_[SIZE]; + + // Deallocate memory allocated by the buffer. + void deallocate() { + T* data = this->data(); + if (data != store_) Allocator::deallocate(data, this->capacity()); + } + + protected: + void grow(std::size_t size) FMT_OVERRIDE; + + public: + typedef T value_type; + typedef const T &const_reference; + + explicit basic_memory_buffer(const Allocator &alloc = Allocator()) + : Allocator(alloc) { + this->set(store_, SIZE); + } + ~basic_memory_buffer() { deallocate(); } + + private: + // Move data from other to this buffer. + void move(basic_memory_buffer &other) { + Allocator &this_alloc = *this, &other_alloc = other; + this_alloc = std::move(other_alloc); + T* data = other.data(); + std::size_t size = other.size(), capacity = other.capacity(); + if (data == other.store_) { + this->set(store_, capacity); + std::uninitialized_copy(other.store_, other.store_ + size, + internal::make_checked(store_, capacity)); + } else { + this->set(data, capacity); + // Set pointer to the inline array so that delete is not called + // when deallocating. + other.set(other.store_, 0); + } + this->resize(size); + } + + public: + /** + \rst + Constructs a :class:`fmt::basic_memory_buffer` object moving the content + of the other object to it. + \endrst + */ + basic_memory_buffer(basic_memory_buffer &&other) { + move(other); + } + + /** + \rst + Moves the content of the other ``basic_memory_buffer`` object to this one. + \endrst + */ + basic_memory_buffer &operator=(basic_memory_buffer &&other) { + assert(this != &other); + deallocate(); + move(other); + return *this; + } + + // Returns a copy of the allocator associated with this buffer. + Allocator get_allocator() const { return *this; } +}; + +template +void basic_memory_buffer::grow(std::size_t size) { + std::size_t old_capacity = this->capacity(); + std::size_t new_capacity = old_capacity + old_capacity / 2; + if (size > new_capacity) + new_capacity = size; + T *old_data = this->data(); + T *new_data = internal::allocate(*this, new_capacity); + // The following code doesn't throw, so the raw pointer above doesn't leak. + std::uninitialized_copy(old_data, old_data + this->size(), + internal::make_checked(new_data, new_capacity)); + this->set(new_data, new_capacity); + // deallocate must not throw according to the standard, but even if it does, + // the buffer already uses the new storage and will deallocate it in + // destructor. + if (old_data != store_) + Allocator::deallocate(old_data, old_capacity); +} + +typedef basic_memory_buffer memory_buffer; +typedef basic_memory_buffer wmemory_buffer; + +namespace internal { + +template +struct char_traits; + +template <> +struct char_traits { + // Formats a floating-point number. + template + FMT_API static int format_float(char *buffer, std::size_t size, + const char *format, int precision, T value); +}; + +template <> +struct char_traits { + template + FMT_API static int format_float(wchar_t *buffer, std::size_t size, + const wchar_t *format, int precision, T value); +}; + +#if FMT_USE_EXTERN_TEMPLATES +extern template int char_traits::format_float( + char *buffer, std::size_t size, const char* format, int precision, + double value); +extern template int char_traits::format_float( + char *buffer, std::size_t size, const char* format, int precision, + long double value); + +extern template int char_traits::format_float( + wchar_t *buffer, std::size_t size, const wchar_t* format, int precision, + double value); +extern template int char_traits::format_float( + wchar_t *buffer, std::size_t size, const wchar_t* format, int precision, + long double value); +#endif + +template +inline typename std::enable_if< + is_contiguous::value, + typename checked::type>::type + reserve(std::back_insert_iterator &it, std::size_t n) { + Container &c = internal::get_container(it); + std::size_t size = c.size(); + c.resize(size + n); + return make_checked(&c[size], n); +} + +template +inline Iterator &reserve(Iterator &it, std::size_t) { return it; } + +template +class null_terminating_iterator; + +template +FMT_CONSTEXPR_DECL const Char *pointer_from(null_terminating_iterator it); + +// An output iterator that counts the number of objects written to it and +// discards them. +template +class counting_iterator { + private: + std::size_t count_; + mutable T blackhole_; + + public: + typedef std::output_iterator_tag iterator_category; + typedef T value_type; + typedef std::ptrdiff_t difference_type; + typedef T* pointer; + typedef T& reference; + typedef counting_iterator _Unchecked_type; // Mark iterator as checked. + + counting_iterator(): count_(0) {} + + std::size_t count() const { return count_; } + + counting_iterator& operator++() { + ++count_; + return *this; + } + + counting_iterator operator++(int) { + auto it = *this; + ++*this; + return it; + } + + T &operator*() const { return blackhole_; } +}; + +template +class truncating_iterator_base { + protected: + OutputIt out_; + std::size_t limit_; + std::size_t count_; + + truncating_iterator_base(OutputIt out, std::size_t limit) + : out_(out), limit_(limit), count_(0) {} + + public: + typedef std::output_iterator_tag iterator_category; + typedef void difference_type; + typedef void pointer; + typedef void reference; + typedef truncating_iterator_base _Unchecked_type; // Mark iterator as checked. + + OutputIt base() const { return out_; } + std::size_t count() const { return count_; } +}; + +// An output iterator that truncates the output and counts the number of objects +// written to it. +template ::value_type>::type> +class truncating_iterator; + +template +class truncating_iterator: + public truncating_iterator_base { + typedef std::iterator_traits traits; + + mutable typename traits::value_type blackhole_; + + public: + typedef typename traits::value_type value_type; + + truncating_iterator(OutputIt out, std::size_t limit) + : truncating_iterator_base(out, limit) {} + + truncating_iterator& operator++() { + if (this->count_++ < this->limit_) + ++this->out_; + return *this; + } + + truncating_iterator operator++(int) { + auto it = *this; + ++*this; + return it; + } + + value_type& operator*() const { + return this->count_ < this->limit_ ? *this->out_ : blackhole_; + } +}; + +template +class truncating_iterator: + public truncating_iterator_base { + public: + typedef typename OutputIt::container_type::value_type value_type; + + truncating_iterator(OutputIt out, std::size_t limit) + : truncating_iterator_base(out, limit) {} + + truncating_iterator& operator=(value_type val) { + if (this->count_++ < this->limit_) + this->out_ = val; + return *this; + } + + truncating_iterator& operator++() { return *this; } + truncating_iterator& operator++(int) { return *this; } + truncating_iterator& operator*() { return *this; } +}; + +// Returns true if value is negative, false otherwise. +// Same as (value < 0) but doesn't produce warnings if T is an unsigned type. +template +FMT_CONSTEXPR typename std::enable_if< + std::numeric_limits::is_signed, bool>::type is_negative(T value) { + return value < 0; +} +template +FMT_CONSTEXPR typename std::enable_if< + !std::numeric_limits::is_signed, bool>::type is_negative(T) { + return false; +} + +template +struct int_traits { + // Smallest of uint32_t and uint64_t that is large enough to represent + // all values of T. + typedef typename std::conditional< + std::numeric_limits::digits <= 32, uint32_t, uint64_t>::type main_type; +}; + +// Static data is placed in this class template to allow header-only +// configuration. +template +struct FMT_API basic_data { + static const uint32_t POWERS_OF_10_32[]; + static const uint32_t ZERO_OR_POWERS_OF_10_32[]; + static const uint64_t ZERO_OR_POWERS_OF_10_64[]; + static const uint64_t POW10_SIGNIFICANDS[]; + static const int16_t POW10_EXPONENTS[]; + static const char DIGITS[]; + static const char FOREGROUND_COLOR[]; + static const char BACKGROUND_COLOR[]; + static const char RESET_COLOR[]; + static const wchar_t WRESET_COLOR[]; +}; + +#if FMT_USE_EXTERN_TEMPLATES +extern template struct basic_data; +#endif + +typedef basic_data<> data; + +#ifdef FMT_BUILTIN_CLZLL +// Returns the number of decimal digits in n. Leading zeros are not counted +// except for n == 0 in which case count_digits returns 1. +inline int count_digits(uint64_t n) { + // Based on http://graphics.stanford.edu/~seander/bithacks.html#IntegerLog10 + // and the benchmark https://github.com/localvoid/cxx-benchmark-count-digits. + int t = (64 - FMT_BUILTIN_CLZLL(n | 1)) * 1233 >> 12; + return t - (n < data::ZERO_OR_POWERS_OF_10_64[t]) + 1; +} +#else +// Fallback version of count_digits used when __builtin_clz is not available. +inline int count_digits(uint64_t n) { + int count = 1; + for (;;) { + // Integer division is slow so do it for a group of four digits instead + // of for every digit. The idea comes from the talk by Alexandrescu + // "Three Optimization Tips for C++". See speed-test for a comparison. + if (n < 10) return count; + if (n < 100) return count + 1; + if (n < 1000) return count + 2; + if (n < 10000) return count + 3; + n /= 10000u; + count += 4; + } +} +#endif + +template +inline size_t count_code_points(basic_string_view s) { return s.size(); } + +// Counts the number of code points in a UTF-8 string. +FMT_API size_t count_code_points(basic_string_view s); + +inline char8_t to_char8_t(char c) { return static_cast(c); } + +template +struct needs_conversion: std::integral_constant::value_type, char>::value && + std::is_same::value> {}; + +template +typename std::enable_if< + !needs_conversion::value, OutputIt>::type + copy_str(InputIt begin, InputIt end, OutputIt it) { + return std::copy(begin, end, it); +} + +template +typename std::enable_if< + needs_conversion::value, OutputIt>::type + copy_str(InputIt begin, InputIt end, OutputIt it) { + return std::transform(begin, end, it, to_char8_t); +} + +#if FMT_HAS_CPP_ATTRIBUTE(always_inline) +# define FMT_ALWAYS_INLINE __attribute__((always_inline)) +#else +# define FMT_ALWAYS_INLINE +#endif + +template +inline char *lg(uint32_t n, Handler h) FMT_ALWAYS_INLINE; + +// Computes g = floor(log10(n)) and calls h.on(n); +template +inline char *lg(uint32_t n, Handler h) { + return n < 100 ? n < 10 ? h.template on<0>(n) : h.template on<1>(n) + : n < 1000000 + ? n < 10000 ? n < 1000 ? h.template on<2>(n) + : h.template on<3>(n) + : n < 100000 ? h.template on<4>(n) + : h.template on<5>(n) + : n < 100000000 ? n < 10000000 ? h.template on<6>(n) + : h.template on<7>(n) + : n < 1000000000 ? h.template on<8>(n) + : h.template on<9>(n); +} + +// An lg handler that formats a decimal number. +// Usage: lg(n, decimal_formatter(buffer)); +class decimal_formatter { + private: + char *buffer_; + + void write_pair(unsigned N, uint32_t index) { + std::memcpy(buffer_ + N, data::DIGITS + index * 2, 2); + } + + public: + explicit decimal_formatter(char *buf) : buffer_(buf) {} + + template char *on(uint32_t u) { + if (N == 0) { + *buffer_ = static_cast(u) + '0'; + } else if (N == 1) { + write_pair(0, u); + } else { + // The idea of using 4.32 fixed-point numbers is based on + // https://github.com/jeaiii/itoa + unsigned n = N - 1; + unsigned a = n / 5 * n * 53 / 16; + uint64_t t = ((1ULL << (32 + a)) / + data::ZERO_OR_POWERS_OF_10_32[n] + 1 - n / 9); + t = ((t * u) >> a) + n / 5 * 4; + write_pair(0, t >> 32); + for (unsigned i = 2; i < N; i += 2) { + t = 100ULL * static_cast(t); + write_pair(i, t >> 32); + } + if (N % 2 == 0) { + buffer_[N] = static_cast( + (10ULL * static_cast(t)) >> 32) + '0'; + } + } + return buffer_ += N + 1; + } +}; + +// An lg handler that formats a decimal number with a terminating null. +class decimal_formatter_null : public decimal_formatter { + public: + explicit decimal_formatter_null(char *buf) : decimal_formatter(buf) {} + + template char *on(uint32_t u) { + char *buf = decimal_formatter::on(u); + *buf = '\0'; + return buf; + } +}; + +#ifdef FMT_BUILTIN_CLZ +// Optional version of count_digits for better performance on 32-bit platforms. +inline int count_digits(uint32_t n) { + int t = (32 - FMT_BUILTIN_CLZ(n | 1)) * 1233 >> 12; + return t - (n < data::ZERO_OR_POWERS_OF_10_32[t]) + 1; +} +#endif + +// A functor that doesn't add a thousands separator. +struct no_thousands_sep { + typedef char char_type; + + template + void operator()(Char *) {} + + enum { size = 0 }; +}; + +// A functor that adds a thousands separator. +template +class add_thousands_sep { + private: + basic_string_view sep_; + + // Index of a decimal digit with the least significant digit having index 0. + unsigned digit_index_; + + public: + typedef Char char_type; + + explicit add_thousands_sep(basic_string_view sep) + : sep_(sep), digit_index_(0) {} + + void operator()(Char *&buffer) { + if (++digit_index_ % 3 != 0) + return; + buffer -= sep_.size(); + std::uninitialized_copy(sep_.data(), sep_.data() + sep_.size(), + internal::make_checked(buffer, sep_.size())); + } + + enum { size = 1 }; +}; + +template +FMT_API Char thousands_sep_impl(locale_ref loc); + +template +inline Char thousands_sep(locale_ref loc) { + return Char(thousands_sep_impl(loc)); +} + +template <> +inline wchar_t thousands_sep(locale_ref loc) { + return thousands_sep_impl(loc); +} + +// Formats a decimal unsigned integer value writing into buffer. +// thousands_sep is a functor that is called after writing each char to +// add a thousands separator if necessary. +template +inline Char *format_decimal(Char *buffer, UInt value, int num_digits, + ThousandsSep thousands_sep) { + FMT_ASSERT(num_digits >= 0, "invalid digit count"); + buffer += num_digits; + Char *end = buffer; + while (value >= 100) { + // Integer division is slow so do it for a group of two digits instead + // of for every digit. The idea comes from the talk by Alexandrescu + // "Three Optimization Tips for C++". See speed-test for a comparison. + unsigned index = static_cast((value % 100) * 2); + value /= 100; + *--buffer = static_cast(data::DIGITS[index + 1]); + thousands_sep(buffer); + *--buffer = static_cast(data::DIGITS[index]); + thousands_sep(buffer); + } + if (value < 10) { + *--buffer = static_cast('0' + value); + return end; + } + unsigned index = static_cast(value * 2); + *--buffer = static_cast(data::DIGITS[index + 1]); + thousands_sep(buffer); + *--buffer = static_cast(data::DIGITS[index]); + return end; +} + +template +inline Iterator format_decimal( + Iterator out, UInt value, int num_digits, ThousandsSep sep) { + FMT_ASSERT(num_digits >= 0, "invalid digit count"); + typedef typename ThousandsSep::char_type char_type; + // Buffer should be large enough to hold all digits (<= digits10 + 1). + enum { max_size = std::numeric_limits::digits10 + 1 }; + FMT_ASSERT(ThousandsSep::size <= 1, "invalid separator"); + char_type buffer[max_size + max_size / 3]; + auto end = format_decimal(buffer, value, num_digits, sep); + return internal::copy_str(buffer, end, out); +} + +template +inline It format_decimal(It out, UInt value, int num_digits) { + return format_decimal(out, value, num_digits, no_thousands_sep()); +} + +template +inline Char *format_uint(Char *buffer, UInt value, int num_digits, + bool upper = false) { + buffer += num_digits; + Char *end = buffer; + do { + const char *digits = upper ? "0123456789ABCDEF" : "0123456789abcdef"; + unsigned digit = (value & ((1 << BASE_BITS) - 1)); + *--buffer = static_cast(BASE_BITS < 4 ? static_cast('0' + digit) + : digits[digit]); + } while ((value >>= BASE_BITS) != 0); + return end; +} + +template +inline It format_uint(It out, UInt value, int num_digits, + bool upper = false) { + // Buffer should be large enough to hold all digits (digits / BASE_BITS + 1) + // and null. + char buffer[std::numeric_limits::digits / BASE_BITS + 2]; + format_uint(buffer, value, num_digits, upper); + return internal::copy_str(buffer, buffer + num_digits, out); +} + +#ifndef _WIN32 +# define FMT_USE_WINDOWS_H 0 +#elif !defined(FMT_USE_WINDOWS_H) +# define FMT_USE_WINDOWS_H 1 +#endif + +// Define FMT_USE_WINDOWS_H to 0 to disable use of windows.h. +// All the functionality that relies on it will be disabled too. +#if FMT_USE_WINDOWS_H +// A converter from UTF-8 to UTF-16. +// It is only provided for Windows since other systems support UTF-8 natively. +class utf8_to_utf16 { + private: + wmemory_buffer buffer_; + + public: + FMT_API explicit utf8_to_utf16(string_view s); + operator wstring_view() const { return wstring_view(&buffer_[0], size()); } + size_t size() const { return buffer_.size() - 1; } + const wchar_t *c_str() const { return &buffer_[0]; } + std::wstring str() const { return std::wstring(&buffer_[0], size()); } +}; + +// A converter from UTF-16 to UTF-8. +// It is only provided for Windows since other systems support UTF-8 natively. +class utf16_to_utf8 { + private: + memory_buffer buffer_; + + public: + utf16_to_utf8() {} + FMT_API explicit utf16_to_utf8(wstring_view s); + operator string_view() const { return string_view(&buffer_[0], size()); } + size_t size() const { return buffer_.size() - 1; } + const char *c_str() const { return &buffer_[0]; } + std::string str() const { return std::string(&buffer_[0], size()); } + + // Performs conversion returning a system error code instead of + // throwing exception on conversion error. This method may still throw + // in case of memory allocation error. + FMT_API int convert(wstring_view s); +}; + +FMT_API void format_windows_error(fmt::internal::buffer &out, int error_code, + fmt::string_view message) FMT_NOEXCEPT; +#endif + +template +struct null {}; +} // namespace internal + +enum alignment { + ALIGN_DEFAULT, ALIGN_LEFT, ALIGN_RIGHT, ALIGN_CENTER, ALIGN_NUMERIC +}; + +// Flags. +enum { SIGN_FLAG = 1, PLUS_FLAG = 2, MINUS_FLAG = 4, HASH_FLAG = 8 }; + +// An alignment specifier. +struct align_spec { + unsigned width_; + // Fill is always wchar_t and cast to char if necessary to avoid having + // two specialization of AlignSpec and its subclasses. + wchar_t fill_; + alignment align_; + + FMT_CONSTEXPR align_spec() : width_(0), fill_(' '), align_(ALIGN_DEFAULT) {} + FMT_CONSTEXPR unsigned width() const { return width_; } + FMT_CONSTEXPR wchar_t fill() const { return fill_; } + FMT_CONSTEXPR alignment align() const { return align_; } +}; + +struct core_format_specs { + int precision; + uint_least8_t flags; + char type; + + FMT_CONSTEXPR core_format_specs() : precision(-1), flags(0), type(0) {} + FMT_CONSTEXPR bool has(unsigned f) const { return (flags & f) != 0; } +}; + +// Format specifiers. +template +struct basic_format_specs : align_spec, core_format_specs { + FMT_CONSTEXPR basic_format_specs() {} +}; + +typedef basic_format_specs format_specs; + +template +FMT_CONSTEXPR unsigned basic_parse_context::next_arg_id() { + if (next_arg_id_ >= 0) + return internal::to_unsigned(next_arg_id_++); + on_error("cannot switch from manual to automatic argument indexing"); + return 0; +} + +namespace internal { + +// Formats value using Grisu2 algorithm: +// https://www.cs.tufts.edu/~nr/cs257/archive/florian-loitsch/printf.pdf +template +FMT_API typename std::enable_if::type + grisu2_format(Double value, buffer &buf, core_format_specs); +template +inline typename std::enable_if::type + grisu2_format(Double, buffer &, core_format_specs) { return false; } + +template +void sprintf_format(Double, internal::buffer &, core_format_specs); + +template +FMT_CONSTEXPR void handle_int_type_spec(char spec, Handler &&handler) { + switch (spec) { + case 0: case 'd': + handler.on_dec(); + break; + case 'x': case 'X': + handler.on_hex(); + break; + case 'b': case 'B': + handler.on_bin(); + break; + case 'o': + handler.on_oct(); + break; + case 'n': + handler.on_num(); + break; + default: + handler.on_error(); + } +} + +template +FMT_CONSTEXPR void handle_float_type_spec(char spec, Handler &&handler) { + switch (spec) { + case 0: case 'g': case 'G': + handler.on_general(); + break; + case 'e': case 'E': + handler.on_exp(); + break; + case 'f': case 'F': + handler.on_fixed(); + break; + case 'a': case 'A': + handler.on_hex(); + break; + default: + handler.on_error(); + break; + } +} + +template +FMT_CONSTEXPR void handle_char_specs( + const basic_format_specs *specs, Handler &&handler) { + if (!specs) return handler.on_char(); + if (specs->type && specs->type != 'c') return handler.on_int(); + if (specs->align() == ALIGN_NUMERIC || specs->flags != 0) + handler.on_error("invalid format specifier for char"); + handler.on_char(); +} + +template +FMT_CONSTEXPR void handle_cstring_type_spec(Char spec, Handler &&handler) { + if (spec == 0 || spec == 's') + handler.on_string(); + else if (spec == 'p') + handler.on_pointer(); + else + handler.on_error("invalid type specifier"); +} + +template +FMT_CONSTEXPR void check_string_type_spec(Char spec, ErrorHandler &&eh) { + if (spec != 0 && spec != 's') + eh.on_error("invalid type specifier"); +} + +template +FMT_CONSTEXPR void check_pointer_type_spec(Char spec, ErrorHandler &&eh) { + if (spec != 0 && spec != 'p') + eh.on_error("invalid type specifier"); +} + +template +class int_type_checker : private ErrorHandler { + public: + FMT_CONSTEXPR explicit int_type_checker(ErrorHandler eh) : ErrorHandler(eh) {} + + FMT_CONSTEXPR void on_dec() {} + FMT_CONSTEXPR void on_hex() {} + FMT_CONSTEXPR void on_bin() {} + FMT_CONSTEXPR void on_oct() {} + FMT_CONSTEXPR void on_num() {} + + FMT_CONSTEXPR void on_error() { + ErrorHandler::on_error("invalid type specifier"); + } +}; + +template +class float_type_checker : private ErrorHandler { + public: + FMT_CONSTEXPR explicit float_type_checker(ErrorHandler eh) + : ErrorHandler(eh) {} + + FMT_CONSTEXPR void on_general() {} + FMT_CONSTEXPR void on_exp() {} + FMT_CONSTEXPR void on_fixed() {} + FMT_CONSTEXPR void on_hex() {} + + FMT_CONSTEXPR void on_error() { + ErrorHandler::on_error("invalid type specifier"); + } +}; + +template +class char_specs_checker : public ErrorHandler { + private: + char type_; + + public: + FMT_CONSTEXPR char_specs_checker(char type, ErrorHandler eh) + : ErrorHandler(eh), type_(type) {} + + FMT_CONSTEXPR void on_int() { + handle_int_type_spec(type_, int_type_checker(*this)); + } + FMT_CONSTEXPR void on_char() {} +}; + +template +class cstring_type_checker : public ErrorHandler { + public: + FMT_CONSTEXPR explicit cstring_type_checker(ErrorHandler eh) + : ErrorHandler(eh) {} + + FMT_CONSTEXPR void on_string() {} + FMT_CONSTEXPR void on_pointer() {} +}; + +template +void arg_map::init(const basic_format_args &args) { + if (map_) + return; + map_ = new entry[args.max_size()]; + if (args.is_packed()) { + for (unsigned i = 0;/*nothing*/; ++i) { + internal::type arg_type = args.type(i); + switch (arg_type) { + case internal::none_type: + return; + case internal::named_arg_type: + push_back(args.values_[i]); + break; + default: + break; // Do nothing. + } + } + } + for (unsigned i = 0; ; ++i) { + switch (args.args_[i].type_) { + case internal::none_type: + return; + case internal::named_arg_type: + push_back(args.args_[i].value_); + break; + default: + break; // Do nothing. + } + } +} + +template +class arg_formatter_base { + public: + typedef typename Range::value_type char_type; + typedef decltype(internal::declval().begin()) iterator; + typedef basic_format_specs format_specs; + + private: + typedef basic_writer writer_type; + writer_type writer_; + format_specs *specs_; + + struct char_writer { + char_type value; + + size_t size() const { return 1; } + size_t width() const { return 1; } + + template + void operator()(It &&it) const { *it++ = value; } + }; + + void write_char(char_type value) { + if (specs_) + writer_.write_padded(*specs_, char_writer{value}); + else + writer_.write(value); + } + + void write_pointer(const void *p) { + format_specs specs = specs_ ? *specs_ : format_specs(); + specs.flags = HASH_FLAG; + specs.type = 'x'; + writer_.write_int(reinterpret_cast(p), specs); + } + + protected: + writer_type &writer() { return writer_; } + format_specs *spec() { return specs_; } + iterator out() { return writer_.out(); } + + void write(bool value) { + string_view sv(value ? "true" : "false"); + specs_ ? writer_.write(sv, *specs_) : writer_.write(sv); + } + + void write(const char_type *value) { + if (!value) + FMT_THROW(format_error("string pointer is null")); + auto length = std::char_traits::length(value); + basic_string_view sv(value, length); + specs_ ? writer_.write(sv, *specs_) : writer_.write(sv); + } + + public: + arg_formatter_base(Range r, format_specs *s, locale_ref loc) + : writer_(r, loc), specs_(s) {} + + iterator operator()(monostate) { + FMT_ASSERT(false, "invalid argument type"); + return out(); + } + + template + typename std::enable_if< + std::is_integral::value || std::is_same::value, + iterator>::type operator()(T value) { + // MSVC2013 fails to compile separate overloads for bool and char_type so + // use std::is_same instead. + if (std::is_same::value) { + if (specs_ && specs_->type) + return (*this)(value ? 1 : 0); + write(value != 0); + } else if (std::is_same::value) { + internal::handle_char_specs( + specs_, char_spec_handler(*this, static_cast(value))); + } else { + specs_ ? writer_.write_int(value, *specs_) : writer_.write(value); + } + return out(); + } + + template + typename std::enable_if::value, iterator>::type + operator()(T value) { + writer_.write_double(value, specs_ ? *specs_ : format_specs()); + return out(); + } + + struct char_spec_handler : internal::error_handler { + arg_formatter_base &formatter; + char_type value; + + char_spec_handler(arg_formatter_base& f, char_type val) + : formatter(f), value(val) {} + + void on_int() { + if (formatter.specs_) + formatter.writer_.write_int(value, *formatter.specs_); + else + formatter.writer_.write(value); + } + void on_char() { formatter.write_char(value); } + }; + + struct cstring_spec_handler : internal::error_handler { + arg_formatter_base &formatter; + const char_type *value; + + cstring_spec_handler(arg_formatter_base &f, const char_type *val) + : formatter(f), value(val) {} + + void on_string() { formatter.write(value); } + void on_pointer() { formatter.write_pointer(value); } + }; + + iterator operator()(const char_type *value) { + if (!specs_) return write(value), out(); + internal::handle_cstring_type_spec( + specs_->type, cstring_spec_handler(*this, value)); + return out(); + } + + iterator operator()(basic_string_view value) { + if (specs_) { + internal::check_string_type_spec( + specs_->type, internal::error_handler()); + writer_.write(value, *specs_); + } else { + writer_.write(value); + } + return out(); + } + + iterator operator()(const void *value) { + if (specs_) + check_pointer_type_spec(specs_->type, internal::error_handler()); + write_pointer(value); + return out(); + } +}; + +template +FMT_CONSTEXPR bool is_name_start(Char c) { + return ('a' <= c && c <= 'z') || ('A' <= c && c <= 'Z') || '_' == c; +} + +// Parses the range [begin, end) as an unsigned integer. This function assumes +// that the range is non-empty and the first character is a digit. +template +FMT_CONSTEXPR unsigned parse_nonnegative_int( + const Char *&begin, const Char *end, ErrorHandler &&eh) { + assert(begin != end && '0' <= *begin && *begin <= '9'); + if (*begin == '0') { + ++begin; + return 0; + } + unsigned value = 0; + // Convert to unsigned to prevent a warning. + unsigned max_int = (std::numeric_limits::max)(); + unsigned big = max_int / 10; + do { + // Check for overflow. + if (value > big) { + value = max_int + 1; + break; + } + value = value * 10 + unsigned(*begin - '0'); + ++begin; + } while (begin != end && '0' <= *begin && *begin <= '9'); + if (value > max_int) + eh.on_error("number is too big"); + return value; +} + +template +class custom_formatter: public function { + private: + Context &ctx_; + + public: + explicit custom_formatter(Context &ctx): ctx_(ctx) {} + + bool operator()(typename basic_format_arg::handle h) const { + h.format(ctx_); + return true; + } + + template + bool operator()(T) const { return false; } +}; + +template +struct is_integer { + enum { + value = std::is_integral::value && !std::is_same::value && + !std::is_same::value && !std::is_same::value + }; +}; + +template +class width_checker: public function { + public: + explicit FMT_CONSTEXPR width_checker(ErrorHandler &eh) : handler_(eh) {} + + template + FMT_CONSTEXPR + typename std::enable_if< + is_integer::value, unsigned long long>::type operator()(T value) { + if (is_negative(value)) + handler_.on_error("negative width"); + return static_cast(value); + } + + template + FMT_CONSTEXPR typename std::enable_if< + !is_integer::value, unsigned long long>::type operator()(T) { + handler_.on_error("width is not integer"); + return 0; + } + + private: + ErrorHandler &handler_; +}; + +template +class precision_checker: public function { + public: + explicit FMT_CONSTEXPR precision_checker(ErrorHandler &eh) : handler_(eh) {} + + template + FMT_CONSTEXPR typename std::enable_if< + is_integer::value, unsigned long long>::type operator()(T value) { + if (is_negative(value)) + handler_.on_error("negative precision"); + return static_cast(value); + } + + template + FMT_CONSTEXPR typename std::enable_if< + !is_integer::value, unsigned long long>::type operator()(T) { + handler_.on_error("precision is not integer"); + return 0; + } + + private: + ErrorHandler &handler_; +}; + +// A format specifier handler that sets fields in basic_format_specs. +template +class specs_setter { + public: + explicit FMT_CONSTEXPR specs_setter(basic_format_specs &specs): + specs_(specs) {} + + FMT_CONSTEXPR specs_setter(const specs_setter &other): specs_(other.specs_) {} + + FMT_CONSTEXPR void on_align(alignment align) { specs_.align_ = align; } + FMT_CONSTEXPR void on_fill(Char fill) { specs_.fill_ = fill; } + FMT_CONSTEXPR void on_plus() { specs_.flags |= SIGN_FLAG | PLUS_FLAG; } + FMT_CONSTEXPR void on_minus() { specs_.flags |= MINUS_FLAG; } + FMT_CONSTEXPR void on_space() { specs_.flags |= SIGN_FLAG; } + FMT_CONSTEXPR void on_hash() { specs_.flags |= HASH_FLAG; } + + FMT_CONSTEXPR void on_zero() { + specs_.align_ = ALIGN_NUMERIC; + specs_.fill_ = '0'; + } + + FMT_CONSTEXPR void on_width(unsigned width) { specs_.width_ = width; } + FMT_CONSTEXPR void on_precision(unsigned precision) { + specs_.precision = static_cast(precision); + } + FMT_CONSTEXPR void end_precision() {} + + FMT_CONSTEXPR void on_type(Char type) { + specs_.type = static_cast(type); + } + + protected: + basic_format_specs &specs_; +}; + +// A format specifier handler that checks if specifiers are consistent with the +// argument type. +template +class specs_checker : public Handler { + public: + FMT_CONSTEXPR specs_checker(const Handler& handler, internal::type arg_type) + : Handler(handler), arg_type_(arg_type) {} + + FMT_CONSTEXPR specs_checker(const specs_checker &other) + : Handler(other), arg_type_(other.arg_type_) {} + + FMT_CONSTEXPR void on_align(alignment align) { + if (align == ALIGN_NUMERIC) + require_numeric_argument(); + Handler::on_align(align); + } + + FMT_CONSTEXPR void on_plus() { + check_sign(); + Handler::on_plus(); + } + + FMT_CONSTEXPR void on_minus() { + check_sign(); + Handler::on_minus(); + } + + FMT_CONSTEXPR void on_space() { + check_sign(); + Handler::on_space(); + } + + FMT_CONSTEXPR void on_hash() { + require_numeric_argument(); + Handler::on_hash(); + } + + FMT_CONSTEXPR void on_zero() { + require_numeric_argument(); + Handler::on_zero(); + } + + FMT_CONSTEXPR void end_precision() { + if (is_integral(arg_type_) || arg_type_ == pointer_type) + this->on_error("precision not allowed for this argument type"); + } + + private: + FMT_CONSTEXPR void require_numeric_argument() { + if (!is_arithmetic(arg_type_)) + this->on_error("format specifier requires numeric argument"); + } + + FMT_CONSTEXPR void check_sign() { + require_numeric_argument(); + if (is_integral(arg_type_) && arg_type_ != int_type && + arg_type_ != long_long_type && arg_type_ != internal::char_type) { + this->on_error("format specifier requires signed argument"); + } + } + + internal::type arg_type_; +}; + +template