init
This commit is contained in:
commit
08bdf29c71
3
.gitignore
vendored
Normal file
3
.gitignore
vendored
Normal file
@ -0,0 +1,3 @@
|
|||||||
|
lidar_driver/build/
|
||||||
|
camera_driver/build/
|
||||||
|
.idea/
|
802
aurco_3d_detect.py
Normal file
802
aurco_3d_detect.py
Normal file
@ -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()
|
535
calibration_mian.py
Normal file
535
calibration_mian.py
Normal file
@ -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)
|
66
camera_driver/CMakeLists.txt
Normal file
66
camera_driver/CMakeLists.txt
Normal file
@ -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})
|
||||||
|
|
1101
camera_driver/CameraDriver.cpp
Normal file
1101
camera_driver/CameraDriver.cpp
Normal file
File diff suppressed because it is too large
Load Diff
99
camera_driver/CameraDriver.h
Normal file
99
camera_driver/CameraDriver.h
Normal file
@ -0,0 +1,99 @@
|
|||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <string.h>
|
||||||
|
#ifndef _WIN32
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <pthread.h>
|
||||||
|
#include <dlfcn.h>
|
||||||
|
#endif // !_WIN32
|
||||||
|
#include "IMVApi.h"
|
||||||
|
#include "IMVDefines.h"
|
||||||
|
|
||||||
|
#include <opencv2/opencv.hpp>
|
||||||
|
#include <opencv2/core.hpp>
|
||||||
|
|
||||||
|
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);
|
||||||
|
|
||||||
|
}
|
798
camera_driver/CameraPublisher.cpp.bak
Normal file
798
camera_driver/CameraPublisher.cpp.bak
Normal file
@ -0,0 +1,798 @@
|
|||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#include <pthread.h>
|
||||||
|
#include <dlfcn.h>
|
||||||
|
#include "IMVApi.h"
|
||||||
|
#include "IMVDefines.h"
|
||||||
|
|
||||||
|
#include <opencv2/opencv.hpp>
|
||||||
|
#include <opencv2/core.hpp>
|
||||||
|
|
||||||
|
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_<double>(3, 3) << 11057.154, 0, 4538.85, 0, 11044.943, 3350.918, 0, 0, 1);
|
||||||
|
// // 设置畸变系数
|
||||||
|
// cv::Mat distCoeffs = (cv::Mat_<double>(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;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
1071
camera_driver/IMVApi.h
Normal file
1071
camera_driver/IMVApi.h
Normal file
File diff suppressed because it is too large
Load Diff
811
camera_driver/IMVDefines.h
Normal file
811
camera_driver/IMVDefines.h
Normal file
@ -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 <stdint.h>
|
||||||
|
#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__
|
1071
camera_driver/include/IMVApi.h
Normal file
1071
camera_driver/include/IMVApi.h
Normal file
File diff suppressed because it is too large
Load Diff
811
camera_driver/include/IMVDefines.h
Normal file
811
camera_driver/include/IMVDefines.h
Normal file
@ -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 <stdint.h>
|
||||||
|
#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__
|
Binary file not shown.
Binary file not shown.
BIN
camera_driver/lib/GenICam/bin/Linux64_x64/libLog_gcc421_v3_0.so
Normal file
BIN
camera_driver/lib/GenICam/bin/Linux64_x64/libLog_gcc421_v3_0.so
Normal file
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
@ -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
|
@ -0,0 +1,741 @@
|
|||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<!--$Header$ -->
|
||||||
|
<!-- ***************************************************************************
|
||||||
|
* (c) 2006 by Basler Vision Technologies
|
||||||
|
* Section: Vision Components
|
||||||
|
* Project: GenApi
|
||||||
|
* Author: Fritz Dierks
|
||||||
|
*
|
||||||
|
* License: This file is published under the license of the EMVA GenICam Standard Group.
|
||||||
|
* A text file describing the legal terms is included in your installation as 'GenICam_license.pdf'.
|
||||||
|
* If for some reason you are missing this file please contact the EMVA or visit the website
|
||||||
|
* (http://www.genicam.org) for a full copy.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE EMVA GENICAM STANDARD GROUP "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 EMVA GENICAM STANDARD GROUP
|
||||||
|
* 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.
|
||||||
|
******************************************************************************** -->
|
||||||
|
<xs:schema xmlns="http://www.genicam.org/GenApi/Version_1_0" xmlns:mstns="http://www.genicam.org/GenApi/Version_1_0" xmlns:xs="http://www.w3.org/2001/XMLSchema" targetNamespace="http://www.genicam.org/GenApi/Version_1_0" elementFormDefault="qualified" id="GenApiSchema_1_0">
|
||||||
|
<xs:element name="RegisterDescription">
|
||||||
|
<xs:complexType>
|
||||||
|
<xs:sequence maxOccurs="unbounded">
|
||||||
|
<xs:group ref="NodesTemplate" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attribute name="ModelName" type="CName_t" use="required" />
|
||||||
|
<xs:attribute name="VendorName" type="CName_t" use="required" />
|
||||||
|
<xs:attribute name="ToolTip" type="xs:string" use="optional" />
|
||||||
|
<xs:attribute name="StandardNameSpace" type="StandardNameSpace_t" use="required" />
|
||||||
|
<xs:attribute name="SchemaMajorVersion" type="nonNegativeHexOrDecimal_t" use="required" fixed="1" />
|
||||||
|
<xs:attribute name="SchemaMinorVersion" type="nonNegativeHexOrDecimal_t" use="required" fixed="0" />
|
||||||
|
<xs:attribute name="SchemaSubMinorVersion" type="nonNegativeHexOrDecimal_t" use="required" />
|
||||||
|
<xs:attribute name="MajorVersion" type="nonNegativeHexOrDecimal_t" use="required" />
|
||||||
|
<xs:attribute name="MinorVersion" type="nonNegativeHexOrDecimal_t" use="required" />
|
||||||
|
<xs:attribute name="SubMinorVersion" type="nonNegativeHexOrDecimal_t" use="required" />
|
||||||
|
<xs:attribute name="ProductGuid" type="xs:string" use="required" />
|
||||||
|
<xs:attribute name="VersionGuid" type="xs:string" use="required" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:key name="IntegerKey">
|
||||||
|
<xs:selector xpath=".//mstns:AdvFeatureLock|.//mstns:Integer|.//mstns:IntKey|.//mstns:IntReg|.//mstns:MaskedIntReg|.//mstns:IntSwissKnife|.//mstns:SmartFeature|.//mstns:StructEntry|.//mstns:IntConverter" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:key name="IntegerOrEnumKey">
|
||||||
|
<xs:selector xpath=".//mstns:AdvFeatureLock|.//mstns:Integer|.//mstns:IntKey|.//mstns:IntReg|.//mstns:MaskedIntReg|.//mstns:IntSwissKnife|.//mstns:SmartFeature|.//mstns:StructEntry|.//mstns:IntConverter|.//mstns:Enumeration" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:key name="IntegerOrBooleanKey">
|
||||||
|
<xs:selector xpath=".//mstns:AdvFeatureLock|.//mstns:Integer|.//mstns:IntKey|.//mstns:IntReg|.//mstns:MaskedIntReg|.//mstns:IntSwissKnife|.//mstns:SmartFeature|.//mstns:StructEntry|.//mstns:IntConverter|.//mstns:Boolean" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:key name="FloatKey">
|
||||||
|
<xs:selector xpath=".//mstns:Converter|.//mstns:Float|.//mstns:FloatReg|.//mstns:SwissKnife" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:key name="StringKey">
|
||||||
|
<xs:selector xpath=".//mstns:StringReg|.//mstns:TextDesc" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:key name="IntegerOrFloatKey">
|
||||||
|
<xs:selector xpath=".//mstns:AdvFeatureLock|.//mstns:Integer|.//mstns:IntKey|.//mstns:IntReg|.//mstns:MaskedIntReg|.//mstns:IntSwissKnife|.//mstns:SmartFeature|.//mstns:StructEntry|.//mstns:Converter|.//mstns:IntConverter|.//mstns:Float|.//mstns:FloatReg|.//mstns:SwissKnife" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:key name="SelectedKey">
|
||||||
|
<xs:selector xpath=".//mstns:Node|.//mstns:IntReg|.//mstns:Enumeration|.//mstns:Integer|.//mstns:MaskedIntReg|.//mstns:Register|.//mstns:IntSwissKnife|.//mstns:Category|.//mstns:TextDesc|.//mstns:IntKey|.//mstns:FloatReg|.//mstns:Float|.//mstns:StringReg|.//mstns:SwissKnife|.//mstns:Converter|.//mstns:IntConverter|.//mstns:Boolean|.//mstns:Command|.//mstns:StructReg/mstns:StructEntry" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:key name="RegisterKey">
|
||||||
|
<xs:selector xpath=".//mstns:Register|.//mstns:AdvFeatureLock|.//mstns:FloatReg|.//mstns:ConfRom|.//mstns:IntReg|.//mstns:MaskedIntReg|.//mstns:SmartFeature|.//mstns:StringReg" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:key name="PortKey">
|
||||||
|
<xs:selector xpath=".//mstns:Port" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:key name="FeatureKey">
|
||||||
|
<xs:selector xpath=".//mstns:Node|.//mstns:IntReg|.//mstns:Enumeration|.//mstns:Integer|.//mstns:MaskedIntReg|.//mstns:Register|.//mstns:IntSwissKnife|.//mstns:Category|.//mstns:TextDesc|.//mstns:IntKey|.//mstns:FloatReg|.//mstns:Float|.//mstns:StringReg|.//mstns:SwissKnife|.//mstns:Converter|.//mstns:IntConverter|.//mstns:Boolean|.//mstns:Command|.//mstns:StructReg/mstns:StructEntry" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:key name="EnumEntryKey">
|
||||||
|
<xs:selector xpath=".//mstns:Enumeration/EnumEntry" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:key name="ConfRomKey">
|
||||||
|
<xs:selector xpath=".//mstns:ConfRom" />
|
||||||
|
<xs:field xpath="@Name" />
|
||||||
|
</xs:key>
|
||||||
|
<xs:keyref name="pAddress" refer="IntegerOrEnumKey">
|
||||||
|
<xs:selector xpath=".//mstns:Register/mstns:pAddress|.//mstns:AdvFeatureLock/mstns:pAddress|.//mstns:FloatReg/mstns:pAddress|.//mstns:ConfRom/mstns:pAddress|.//mstns:IntReg/mstns:pAddress|.//mstns:MaskedIntReg/mstns:pAddress|.//mstns:SmartFeature/mstns:pAddress|.//mstns:StringReg/mstns:pAddress" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pIndex" refer="IntegerKey">
|
||||||
|
<xs:selector xpath=".//mstns:Register/mstns:pIndex|.//mstns:AdvFeatureLock/mstns:pIndex|.//mstns:FloatReg/mstns:pIndex|.//mstns:ConfRom/mstns:pIndex|.//mstns:IntReg/mstns:pIndex|.//mstns:MaskedIntReg/mstns:pIndex|.//mstns:SmartFeature/mstns:pIndex|.//mstns:StringReg/mstns:pIndex" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pLength" refer="IntegerKey">
|
||||||
|
<xs:selector xpath=".//mstns:Register/mstns:pLength|.//mstns:AdvFeatureLock/mstns:pLength|.//mstns:FloatReg/mstns:pLength|.//mstns:ConfRom/mstns:pLength|.//mstns:IntReg/mstns:pLength|.//mstns:MaskedIntReg/mstns:pLength|.//mstns:SmartFeature/mstns:pLength|.//mstns:StringReg/mstns:pLength" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pPort" refer="PortKey">
|
||||||
|
<xs:selector xpath=".//mstns:Register/mstns:pPort|.//mstns:AdvFeatureLock/mstns:pPort|.//mstns:FloatReg/mstns:pPort|.//mstns:ConfRom/mstns:pPort|.//mstns:IntReg/mstns:pPort|.//mstns:MaskedIntReg/mstns:pPort|.//mstns:SmartFeature/mstns:pPort|.//mstns:StringReg/mstns:pPort" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pFeature" refer="FeatureKey">
|
||||||
|
<xs:selector xpath=".//mstns:Category/mstns:pFeature" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pSelected" refer="SelectedKey">
|
||||||
|
<xs:selector xpath=".//mstns:Enumeration/mstns:pSelected|.//mstns:Integer/mstns:pSelected|.//mstns:IntReg/mstns:pSelected|.//mstns:MaskedIntReg/mstns:pSelected|.//mstns:StructEntry/mstns:pSelected" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pValue_Integer" refer="IntegerKey">
|
||||||
|
<xs:selector xpath=".//mstns:Enumeration/mstns:pValue|.//mstns:Integer/mstns:pValue|.//mstns:Command/mstns:pValue|.//mstns:Boolean/mstns:pValue" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pMin_Integer" refer="IntegerKey">
|
||||||
|
<xs:selector xpath=".//mstns:Integer/mstns:pMin" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pMax_Integer" refer="IntegerKey">
|
||||||
|
<xs:selector xpath=".//mstns:Integer/mstns:pMax" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pInc_Integer" refer="IntegerKey">
|
||||||
|
<xs:selector xpath=".//mstns:Integer/mstns:pInc" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pValue_Float" refer="FloatKey">
|
||||||
|
<xs:selector xpath=".//mstns:Float/mstns:pValue" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pMin_Float" refer="FloatKey">
|
||||||
|
<xs:selector xpath=".//mstns:Float/mstns:pMin" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pMax_Float" refer="FloatKey">
|
||||||
|
<xs:selector xpath=".//mstns:Float/mstns:pMax" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pValue_IntegerOrFloat" refer="IntegerOrFloatKey">
|
||||||
|
<xs:selector xpath=".//mstns:Converter/mstns:pValue" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pIsImplemented" refer="IntegerOrBooleanKey">
|
||||||
|
<xs:selector xpath=".//mstns:Node/mstns:pIsImplemented|.//mstns:IntReg/mstns:pIsImplemented|.//mstns:Enumeration/mstns:pIsImplemented|.//mstns:Integer/mstns:pIsImplemented|.//mstns:MaskedIntReg/mstns:pIsImplemented|.//mstns:Register/mstns:pIsImplemented|.//mstns:IntSwissKnife/mstns:pIsImplemented|.//mstns:Category/mstns:pIsImplemented|.//mstns:TextDesc/mstns:pIsImplemented|.//mstns:IntKey/mstns:pIsImplemented|.//mstns:FloatReg/mstns:pIsImplemented|.//mstns:Float/mstns:pIsImplemented|.//mstns:StringReg/mstns:pIsImplemented|.//mstns:SwissKnife/mstns:pIsImplemented|.//mstns:Converter/mstns:pIsImplemented|.//mstns:Boolean/mstns:pIsImplemented|.//mstns:Command/mstns:pIsImplemented|.//mstns:StructReg/mstns:StructEntry/mstns:pIsImplemented|.//mstns:EnumEntry/mstns:pIsImplemented|.//mstns:Port/mstns:pIsImplemented|.//mstns:AdvFeatureLock/mstns:pIsImplemented|.//mstns:SmartFeature/mstns:pIsImplemented" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pIsAvailable" refer="IntegerOrBooleanKey">
|
||||||
|
<xs:selector xpath=".//mstns:Node/mstns:pIsAvailable|.//mstns:IntReg/mstns:pIsAvailable|.//mstns:Enumeration/mstns:pIsAvailable|.//mstns:EnumEntry/mstns:pIsAvailable|.//mstns:Integer/mstns:pIsAvailable|.//mstns:MaskedIntReg/mstns:pIsAvailable|.//mstns:Register/mstns:pIsAvailable|.//mstns:IntSwissKnife/mstns:pIsAvailable|.//mstns:Category/mstns:pIsAvailable|.//mstns:TextDesc/mstns:pIsAvailable|.//mstns:IntKey/mstns:pIsAvailable|.//mstns:FloatReg/mstns:pIsAvailable|.//mstns:Float/mstns:pIsAvailable|.//mstns:StringReg/mstns:pIsAvailable|.//mstns:SwissKnife/mstns:pIsAvailable|.//mstns:Converter/mstns:pIsAvailable|.//mstns:Boolean/mstns:pIsAvailable|.//mstns:Command/mstns:pIsAvailable|.//mstns:StructReg/mstns:StructEntry/mstns:pIsAvailable|.//mstns:EnumEntry/mstns:pIsAvailable|.//mstns:Port/mstns:pIsAvailable|.//mstns:AdvFeatureLock/mstns:pIsAvailable|.//mstns:SmartFeature/mstns:pIsAvailable" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pIsLocked" refer="IntegerOrBooleanKey">
|
||||||
|
<xs:selector xpath=".//mstns:Node/mstns:pIsLocked|.//mstns:IntReg/mstns:pIsLocked|.//mstns:Enumeration/mstns:pIsLocked|.//mstns:EnumEntry/mstns:pIsLocked|.//mstns:Integer/mstns:pIsLocked|.//mstns:MaskedIntReg/mstns:pIsLocked|.//mstns:Register/mstns:pIsLocked|.//mstns:IntSwissKnife/mstns:pIsLocked|.//mstns:Category/mstns:pIsLocked|.//mstns:TextDesc/mstns:pIsLocked|.//mstns:IntKey/mstns:pIsLocked|.//mstns:FloatReg/mstns:pIsLocked|.//mstns:Float/mstns:pIsLocked|.//mstns:StringReg/mstns:pIsLocked|.//mstns:SwissKnife/mstns:pIsLocked|.//mstns:Converter/mstns:pIsLocked|.//mstns:Boolean/mstns:pIsLocked|.//mstns:Command/mstns:pIsLocked|.//mstns:StructReg/mstns:StructEntry/mstns:pIsLocked|.//mstns:EnumEntry/mstns:pIsLocked|.//mstns:Port/mstns:pIsLocked|.//mstns:AdvFeatureLock/mstns:pIsLocked|.//mstns:SmartFeature/mstns:pIsLocked" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pVariable_Integer" refer="IntegerKey">
|
||||||
|
<xs:selector xpath=".//mstns:IntSwissKnife/mstns:pVariable|.//mstns:IntConverter/mstns:pVariable" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pVariable_IntegerOrFloat" refer="IntegerOrFloatKey">
|
||||||
|
<xs:selector xpath=".//mstns:SwissKnife/mstns:pVariable|.//mstns:Converter/mstns:pVariable" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pEnumEntry" refer="EnumEntryKey">
|
||||||
|
<xs:selector xpath=".//mstns:Enumeration/mstns:pEnumEntry" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pChunkID" refer="StringKey">
|
||||||
|
<xs:selector xpath=".//mstns:Port/mstns:pChunkID" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="p1212Parser" refer="ConfRomKey">
|
||||||
|
<xs:selector xpath=".//mstns:TextDesc/mstns:p1212Parser|.//mstns:IntKey/mstns:p1212Parser" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pCommandValue" refer="IntegerKey">
|
||||||
|
<xs:selector xpath=".//mstns:Command/mstns:pCommandValue" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
<xs:keyref name="pAlias" refer="FeatureKey">
|
||||||
|
<xs:selector xpath=".//mstns:*/mstns:pAlias" />
|
||||||
|
<xs:field xpath="." />
|
||||||
|
</xs:keyref>
|
||||||
|
</xs:element>
|
||||||
|
<xs:group name="NodesTemplate">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element name="Node" type="NodeType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="Category" type="CategoryType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="Integer" type="IntegerType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="IntReg" type="IntRegType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="MaskedIntReg" type="MaskedIntRegType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="Boolean" type="BooleanType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="Command" type="CommandType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="Enumeration" type="EnumerationType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="EnumEntry" type="EnumEntryType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="Float" type="FloatType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="FloatReg" type="FloatRegType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="StringReg" type="StringRegType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="Register" type="RegisterType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="Converter" type="ConverterType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="IntConverter" type="IntConverterType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="SwissKnife" type="SwissKnifeType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="IntSwissKnife" type="SwissKnifeType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="Port" type="PortType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="ConfRom" type="ConfRomType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="TextDesc" type="TextDescType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="IntKey" type="IntKeyType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="AdvFeatureLock" type="DcamLockType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="SmartFeature" type="SmartFeatureAdrType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="Group" type="GroupType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="StructReg" type="StructRegType" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
</xs:sequence>
|
||||||
|
</xs:group>
|
||||||
|
<xs:complexType name="GroupType">
|
||||||
|
<xs:sequence maxOccurs="unbounded">
|
||||||
|
<xs:group ref="NodesTemplate" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attribute name="Comment" type="xs:string" use="required" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:group name="NodeElementTemplate">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element name="Extension" type="ExtensionType" minOccurs="0" />
|
||||||
|
<xs:element name="ToolTip" type="nonEmptyString_t" minOccurs="0" />
|
||||||
|
<xs:element name="Description" type="nonEmptyString_t" minOccurs="0" />
|
||||||
|
<xs:element name="DisplayName" type="xs:string" minOccurs="0" />
|
||||||
|
<xs:element name="Visibility" type="Visibility_t" default="Beginner" minOccurs="0" />
|
||||||
|
<xs:element name="EventID" type="Hex_t" minOccurs="0" />
|
||||||
|
<xs:element name="pIsImplemented" type="CName_t" minOccurs="0" />
|
||||||
|
<xs:element name="pIsAvailable" type="CName_t" minOccurs="0" />
|
||||||
|
<xs:element name="pIsLocked" type="CName_t" minOccurs="0" />
|
||||||
|
<xs:element name="ImposedAccessMode" type="Access_t" default="RW" minOccurs="0" />
|
||||||
|
<xs:element name="pAlias" type="CName_t" minOccurs="0" />
|
||||||
|
</xs:sequence>
|
||||||
|
</xs:group>
|
||||||
|
<xs:attributeGroup name="NodeAttributeTemplate">
|
||||||
|
<xs:attribute name="Name" type="CName_t" use="required" />
|
||||||
|
<xs:attribute name="NameSpace" type="NameSpace_t" default="Custom" />
|
||||||
|
<!-- This is allowed only for inject files not for target files -->
|
||||||
|
<xs:attribute name="MergePriority" type="MergePriority_t"/>
|
||||||
|
</xs:attributeGroup>
|
||||||
|
<xs:group name="RegisterElementTemplate">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:element name="Streamable" type="YesNo_t" default="No" minOccurs="0" />
|
||||||
|
<xs:choice maxOccurs="unbounded">
|
||||||
|
<xs:element name="Address" type="HexOrDecimal_t" />
|
||||||
|
<xs:element name="IntSwissKnife" type="SwissKnifeType" />
|
||||||
|
<xs:element name="pAddress" type="CName_t" />
|
||||||
|
<xs:element name="pIndex">
|
||||||
|
<xs:complexType>
|
||||||
|
<xs:simpleContent>
|
||||||
|
<xs:extension base="xs:string">
|
||||||
|
<xs:attribute name="Offset" type="HexOrDecimal_t" use="required" />
|
||||||
|
</xs:extension>
|
||||||
|
</xs:simpleContent>
|
||||||
|
</xs:complexType>
|
||||||
|
</xs:element>
|
||||||
|
</xs:choice>
|
||||||
|
<xs:choice>
|
||||||
|
<xs:element name="Length" type="xs:positiveInteger" />
|
||||||
|
<xs:element name="pLength" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="AccessMode" type="Access_t" default="RO" />
|
||||||
|
<xs:element name="pPort" type="CName_t" />
|
||||||
|
<xs:element name="Cachable" type="CachingMode_t" default="WriteThrough" minOccurs="0" />
|
||||||
|
<xs:element name="PollingTime" type="xs:nonNegativeInteger" minOccurs="0" />
|
||||||
|
<xs:element name="pInvalidator" type="CName_t" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
</xs:sequence>
|
||||||
|
</xs:group>
|
||||||
|
<xs:complexType name="NodeType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="CategoryType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:element name="pFeature" type="CName_t" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="IntegerType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:element name="Streamable" type="YesNo_t" default="No" minOccurs="0" />
|
||||||
|
<xs:choice>
|
||||||
|
<xs:element name="Value" type="HexOrDecimal_t" />
|
||||||
|
<xs:element name="pValue" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:choice minOccurs="0">
|
||||||
|
<xs:element name="Min" type="xs:integer" />
|
||||||
|
<xs:element name="pMin" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:choice minOccurs="0">
|
||||||
|
<xs:element name="Max" type="xs:integer" />
|
||||||
|
<xs:element name="pMax" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:choice minOccurs="0">
|
||||||
|
<xs:element name="Inc" type="nonNegativeHexOrDecimal_t" />
|
||||||
|
<xs:element name="pInc" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="Representation" type="Representation_t" minOccurs="0" />
|
||||||
|
<xs:element name="pSelected" type="CName_t" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="IntRegType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="RegisterElementTemplate" />
|
||||||
|
<xs:element name="Sign" type="Sign_t" default="Unsigned" />
|
||||||
|
<xs:element name="Endianess" type="Endianess_t" default="LittleEndian" />
|
||||||
|
<xs:element name="Representation" type="Representation_t" minOccurs="0" />
|
||||||
|
<xs:element name="pSelected" type="CName_t" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="MaskedIntRegType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="RegisterElementTemplate" />
|
||||||
|
<xs:choice>
|
||||||
|
<xs:element name="Bit" type="xs:nonNegativeInteger" />
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element name="LSB" type="xs:nonNegativeInteger" />
|
||||||
|
<xs:element name="MSB" type="xs:nonNegativeInteger" />
|
||||||
|
</xs:sequence>
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="Sign" type="Sign_t" default="Unsigned" minOccurs="0" />
|
||||||
|
<xs:element name="Endianess" type="Endianess_t" default="LittleEndian" />
|
||||||
|
<xs:element name="Representation" type="Representation_t" minOccurs="0" />
|
||||||
|
<xs:element name="pSelected" type="CName_t" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="StructRegType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="RegisterElementTemplate" />
|
||||||
|
<xs:element name="Endianess" type="Endianess_t" default="LittleEndian" />
|
||||||
|
<xs:element name="StructEntry" type="StructEntryType" maxOccurs="unbounded" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attribute name="Comment" type="xs:string" use="required" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="StructEntryType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element name="Extension" type="ExtensionType" minOccurs="0" />
|
||||||
|
<xs:element name="ToolTip" type="nonEmptyString_t" minOccurs="0" />
|
||||||
|
<xs:element name="DisplayName" type="xs:string" minOccurs="0" />
|
||||||
|
<xs:element name="Visibility" type="Visibility_t" default="Beginner" minOccurs="0" />
|
||||||
|
<xs:element name="pIsImplemented" type="CName_t" minOccurs="0" />
|
||||||
|
<xs:element name="pIsAvailable" type="CName_t" minOccurs="0" />
|
||||||
|
<xs:element name="pIsLocked" type="CName_t" minOccurs="0" />
|
||||||
|
<xs:element name="pInvalidator" type="CName_t" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
<xs:element name="AccessMode" type="Access_t" minOccurs="0" />
|
||||||
|
<xs:element name="Cachable" type="CachingMode_t" default="WriteThrough" minOccurs="0" />
|
||||||
|
<xs:element name="PollingTime" type="xs:nonNegativeInteger" minOccurs="0" />
|
||||||
|
<xs:element name="Streamable" type="YesNo_t" default="No" minOccurs="0" />
|
||||||
|
<xs:choice>
|
||||||
|
<xs:element name="Bit" type="xs:nonNegativeInteger" />
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element name="LSB" type="xs:nonNegativeInteger" />
|
||||||
|
<xs:element name="MSB" type="xs:nonNegativeInteger" />
|
||||||
|
</xs:sequence>
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="Sign" type="Sign_t" default="Unsigned" minOccurs="0" />
|
||||||
|
<xs:element name="pSelected" type="CName_t" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="CommandType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:choice>
|
||||||
|
<xs:element name="Value" type="HexOrDecimal_t" />
|
||||||
|
<xs:element name="pValue" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:choice>
|
||||||
|
<xs:element name="CommandValue" type="HexOrDecimal_t" />
|
||||||
|
<xs:element name="pCommandValue" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="PollingTime" type="xs:nonNegativeInteger" minOccurs="0" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="BooleanType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:element name="Streamable" type="YesNo_t" default="No" minOccurs="0" />
|
||||||
|
<xs:choice>
|
||||||
|
<xs:element name="Value" type="xs:boolean" />
|
||||||
|
<xs:element name="pValue" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="OnValue" type="xs:int" minOccurs="0" />
|
||||||
|
<xs:element name="OffValue" type="xs:int" minOccurs="0" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="FloatType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:element name="Streamable" type="YesNo_t" default="No" minOccurs="0" />
|
||||||
|
<xs:choice>
|
||||||
|
<xs:element name="pValue" type="CName_t" />
|
||||||
|
<xs:element name="Value" type="xs:float" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:choice minOccurs="0">
|
||||||
|
<xs:element name="Min" type="xs:float" />
|
||||||
|
<xs:element name="pMin" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:choice minOccurs="0">
|
||||||
|
<xs:element name="Max" type="xs:float" />
|
||||||
|
<xs:element name="pMax" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="Unit" type="nonEmptyString_t" minOccurs="0" />
|
||||||
|
<xs:element name="Representation" type="Representation_t" minOccurs="0" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="ConverterType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:element name="Streamable" type="YesNo_t" default="No" minOccurs="0" />
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element name="pVariable" minOccurs="0" maxOccurs="unbounded">
|
||||||
|
<xs:complexType>
|
||||||
|
<xs:simpleContent>
|
||||||
|
<xs:extension base="xs:string">
|
||||||
|
<xs:attribute name="Name" type="xs:string" use="required" />
|
||||||
|
</xs:extension>
|
||||||
|
</xs:simpleContent>
|
||||||
|
</xs:complexType>
|
||||||
|
</xs:element>
|
||||||
|
<xs:element name="FormulaTo" type="xs:string" />
|
||||||
|
<xs:element name="FormulaFrom" type="xs:string" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:choice>
|
||||||
|
<xs:element name="pValue" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="Unit" type="nonEmptyString_t" minOccurs="0" />
|
||||||
|
<xs:element name="Representation" type="Representation_t" minOccurs="0" />
|
||||||
|
<xs:element name="Slope" type="Slope_t" default="Automatic" minOccurs="0" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="IntConverterType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:element name="Streamable" type="YesNo_t" default="No" minOccurs="0" />
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element name="pVariable" minOccurs="0" maxOccurs="unbounded">
|
||||||
|
<xs:complexType>
|
||||||
|
<xs:simpleContent>
|
||||||
|
<xs:extension base="xs:string">
|
||||||
|
<xs:attribute name="Name" type="xs:string" use="required" />
|
||||||
|
</xs:extension>
|
||||||
|
</xs:simpleContent>
|
||||||
|
</xs:complexType>
|
||||||
|
</xs:element>
|
||||||
|
<xs:element name="FormulaTo" type="xs:string" />
|
||||||
|
<xs:element name="FormulaFrom" type="xs:string" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:choice>
|
||||||
|
<xs:element name="pValue" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="Unit" type="nonEmptyString_t" minOccurs="0" />
|
||||||
|
<xs:element name="Representation" type="Representation_t" minOccurs="0" />
|
||||||
|
<xs:element name="Slope" type="Slope_t" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="FloatRegType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="RegisterElementTemplate" />
|
||||||
|
<xs:element name="Endianess" type="Endianess_t" default="LittleEndian" />
|
||||||
|
<xs:element name="Unit" type="nonEmptyString_t" minOccurs="0" />
|
||||||
|
<xs:element name="Representation" type="Representation_t" minOccurs="0" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="EnumerationType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:element name="Streamable" type="YesNo_t" default="No" minOccurs="0" />
|
||||||
|
<xs:choice maxOccurs="unbounded">
|
||||||
|
<xs:element name="EnumEntry" type="EnumEntryType" />
|
||||||
|
<xs:element name="pEnumEntry" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:choice>
|
||||||
|
<xs:element name="Value" type="HexOrDecimal_t" />
|
||||||
|
<xs:element name="pValue" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="pSelected" type="CName_t" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="EnumEntryType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:element name="Value" type="HexOrDecimal_t" />
|
||||||
|
<xs:element name="Symbolic" type="CName_t" minOccurs="0" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
<!-- Note : this entry is normally generated by the pre-processor only -->
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="StringRegType">
|
||||||
|
<xs:sequence>
|
||||||
|
<!-- TODO should be implemented with RegisterElementTemplate; BUT: pLength -->
|
||||||
|
<xs:group ref="RegisterElementTemplate" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="RegisterType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="RegisterElementTemplate" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="SwissKnifeType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:element name="Streamable" type="YesNo_t" default="No" minOccurs="0" />
|
||||||
|
<xs:element name="pVariable" minOccurs="0" maxOccurs="unbounded">
|
||||||
|
<xs:complexType>
|
||||||
|
<xs:simpleContent>
|
||||||
|
<xs:extension base="xs:string">
|
||||||
|
<xs:attribute name="Name" type="xs:string" use="required" />
|
||||||
|
</xs:extension>
|
||||||
|
</xs:simpleContent>
|
||||||
|
</xs:complexType>
|
||||||
|
</xs:element>
|
||||||
|
<xs:element name="Formula" type="xs:string" />
|
||||||
|
<xs:element name="Representation" type="Representation_t" minOccurs="0" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="PortType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:choice minOccurs="0">
|
||||||
|
<xs:element name="ChunkID" type="Hex_t" />
|
||||||
|
<xs:element name="pChunkID" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="SwapEndianess" type="YesNo_t" default="No" minOccurs="0" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="ConfRomType">
|
||||||
|
<xs:sequence maxOccurs="unbounded">
|
||||||
|
<xs:group ref="NodeElementTemplate" />
|
||||||
|
<xs:element name="Unit" type="HexOrDecimal_t" />
|
||||||
|
<xs:choice maxOccurs="unbounded">
|
||||||
|
<xs:element name="Address" type="nonNegativeHexOrDecimal_t" />
|
||||||
|
<xs:element name="IntSwissKnife" type="SwissKnifeType" />
|
||||||
|
<xs:element name="pAddress" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="Length" type="nonNegativeHexOrDecimal_t" />
|
||||||
|
<xs:element name="pPort" type="CName_t" />
|
||||||
|
<xs:choice minOccurs="0" maxOccurs="unbounded">
|
||||||
|
<xs:element name="TextDesc" type="Key_t" />
|
||||||
|
<xs:element name="IntKey" type="Key_t" />
|
||||||
|
</xs:choice>
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="TextDescType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element name="p1212Parser" type="CName_t" />
|
||||||
|
<xs:element name="Key" type="HexOrDecimal_t" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="IntKeyType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element name="p1212Parser" type="CName_t" />
|
||||||
|
<xs:element name="Key" type="HexOrDecimal_t" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="DcamLockType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:group ref="RegisterElementTemplate" />
|
||||||
|
<xs:element name="FeatureID" type="HexOrDecimal_t" />
|
||||||
|
<xs:element name="Timeout" type="xs:nonNegativeInteger" minOccurs="0" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="SmartFeatureAdrType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element name="FeatureID" type="xs:string" />
|
||||||
|
<xs:choice maxOccurs="unbounded">
|
||||||
|
<xs:element name="Address" type="nonNegativeHexOrDecimal_t" />
|
||||||
|
<xs:element name="IntSwissKnife" type="SwissKnifeType" />
|
||||||
|
<xs:element name="pAddress" type="CName_t" />
|
||||||
|
</xs:choice>
|
||||||
|
<xs:element name="pPort" type="CName_t" />
|
||||||
|
<xs:element name="pIsImplemented" type="CName_t" minOccurs="0" />
|
||||||
|
<xs:element name="pIsAvailable" type="CName_t" minOccurs="0" />
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attributeGroup ref="NodeAttributeTemplate" />
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:complexType name="ExtensionType">
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:any processContents="skip" minOccurs="0" maxOccurs="unbounded" />
|
||||||
|
</xs:sequence>
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:simpleType name="CName_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:pattern value="[A-Za-z][0-9A-Za-z_]*" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="nonEmptyString_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:minLength value="1" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="CachingMode_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:enumeration value="WriteThrough">
|
||||||
|
<xs:annotation>
|
||||||
|
<xs:documentation>Cache on write and write into register</xs:documentation>
|
||||||
|
</xs:annotation>
|
||||||
|
</xs:enumeration>
|
||||||
|
<xs:enumeration value="WriteAround">
|
||||||
|
<xs:annotation>
|
||||||
|
<xs:documentation>Write w/o cache, read updates cache</xs:documentation>
|
||||||
|
</xs:annotation>
|
||||||
|
</xs:enumeration>
|
||||||
|
<xs:enumeration value="NoCache">
|
||||||
|
<xs:annotation>
|
||||||
|
<xs:documentation>Do not perform caching</xs:documentation>
|
||||||
|
</xs:annotation>
|
||||||
|
</xs:enumeration>
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="HexOrDecimal_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:pattern value="(0[xX][0-9A-Fa-f]+)|(-?[0-9]+)" />
|
||||||
|
<!--<xs:pattern value="()|(0x[0-9A-Fa-f]+)"/>-->
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="Hex_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:pattern value="([0-9A-Fa-f][0-9A-Fa-f])+" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="nonNegativeHexOrDecimal_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:pattern value="(0[xX][0-9A-Fa-f]+)|[0-9]+" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="Sign_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:enumeration value="Signed" />
|
||||||
|
<xs:enumeration value="Unsigned" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:complexType name="SwissKnifeConversion_t">
|
||||||
|
<xs:simpleContent>
|
||||||
|
<xs:extension base="xs:string">
|
||||||
|
<xs:attribute name="Input" type="CName_t" use="required" />
|
||||||
|
</xs:extension>
|
||||||
|
</xs:simpleContent>
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:simpleType name="NameSpace_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:enumeration value="Custom" />
|
||||||
|
<xs:enumeration value="Standard" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="StandardNameSpace_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:enumeration value="None" />
|
||||||
|
<xs:enumeration value="IIDC" />
|
||||||
|
<xs:enumeration value="GEV" />
|
||||||
|
<xs:enumeration value="CL" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="Representation_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:enumeration value="Linear" />
|
||||||
|
<xs:enumeration value="Logarithmic" />
|
||||||
|
<xs:enumeration value="Boolean" />
|
||||||
|
<xs:enumeration value="PureNumber" />
|
||||||
|
<xs:enumeration value="HexNumber" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="Access_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:enumeration value="RO" />
|
||||||
|
<xs:enumeration value="WO" />
|
||||||
|
<xs:enumeration value="RW" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="Endianess_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:enumeration value="LittleEndian" />
|
||||||
|
<xs:enumeration value="BigEndian" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="Visibility_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:enumeration value="Beginner" />
|
||||||
|
<xs:enumeration value="Expert" />
|
||||||
|
<xs:enumeration value="Guru" />
|
||||||
|
<xs:enumeration value="Invisible" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="YesNo_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:enumeration value="Yes" />
|
||||||
|
<xs:enumeration value="No" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="MergePriority_t">
|
||||||
|
<xs:restriction base="xs:integer">
|
||||||
|
<xs:enumeration value="-1"/>
|
||||||
|
<xs:enumeration value="0"/>
|
||||||
|
<xs:enumeration value="+1"/>
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:simpleType name="Slope_t">
|
||||||
|
<xs:restriction base="xs:string">
|
||||||
|
<xs:enumeration value="Increasing" />
|
||||||
|
<xs:enumeration value="Decreasing" />
|
||||||
|
<xs:enumeration value="Varying" />
|
||||||
|
<xs:enumeration value="Automatic" />
|
||||||
|
</xs:restriction>
|
||||||
|
</xs:simpleType>
|
||||||
|
<xs:complexType name="Key_t">
|
||||||
|
<xs:simpleContent>
|
||||||
|
<xs:extension base="HexOrDecimal_t">
|
||||||
|
<xs:attribute name="Name" type="CName_t" use="required" />
|
||||||
|
<xs:attribute name="NameSpace" type="NameSpace_t" default="Custom" />
|
||||||
|
</xs:extension>
|
||||||
|
</xs:simpleContent>
|
||||||
|
</xs:complexType>
|
||||||
|
</xs:schema>
|
1221
camera_driver/lib/GenICam/xml/GenApi/GenApiSchema_Version_1_1.xsd
Normal file
1221
camera_driver/lib/GenICam/xml/GenApi/GenApiSchema_Version_1_1.xsd
Normal file
File diff suppressed because it is too large
Load Diff
376
camera_driver/lib/GenICam/xml/GenApi/GenApi_Params_h.xsl
Normal file
376
camera_driver/lib/GenICam/xml/GenApi/GenApi_Params_h.xsl
Normal file
@ -0,0 +1,376 @@
|
|||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<!-- ***************************************************************************
|
||||||
|
* (c) 2004-2008 by Basler Vision Technologies
|
||||||
|
* Section: Vision Components
|
||||||
|
* Project: GenApi
|
||||||
|
* Author: Fritz Dierks
|
||||||
|
* $Header$
|
||||||
|
*
|
||||||
|
* License: This file is published under the license of the EMVA GenICam Standard Group.
|
||||||
|
* A text file describing the legal terms is included in your installation as 'GenICam_license.pdf'.
|
||||||
|
* If for some reason you are missing this file please contact the EMVA or visit the website
|
||||||
|
* (http://www.genicam.org) for a full copy.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE EMVA GENICAM STANDARD GROUP "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 EMVA GENICAM STANDARD GROUP
|
||||||
|
* 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.
|
||||||
|
******************************************************************************** -->
|
||||||
|
|
||||||
|
<xsl:stylesheet version="1.0" xmlns:my_v1_0="http://www.genicam.org/GenApi/Version_1_0" xmlns:my_v1_1="http://www.genicam.org/GenApi/Version_1_1" xmlns:xsl="http://www.w3.org/1999/XSL/Transform">
|
||||||
|
<xsl:output method="text" encoding="UTF-8" media-type="text/plain"/>
|
||||||
|
<xsl:template match="/">
|
||||||
|
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
<!-- Main body -->
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
// (c) 2004-2008 by Basler Vision Technologies
|
||||||
|
// Section: Vision Components
|
||||||
|
// Project: GenApi
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
/*!
|
||||||
|
\file
|
||||||
|
\brief <xsl:value-of select="/RegisterDescription/@ToolTip"/>
|
||||||
|
*/
|
||||||
|
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
// This file is generated automatically
|
||||||
|
// Do not modify!
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
|
||||||
|
<xsl:variable name="NameSpace">
|
||||||
|
<xsl:value-of select="/RegisterDescription/@VendorName"/>_<xsl:value-of select="/RegisterDescription/@ModelName"/>
|
||||||
|
</xsl:variable>
|
||||||
|
|
||||||
|
#ifndef <xsl:value-of select="$NameSpace"/><xsl:text>_PARAMS_H</xsl:text>
|
||||||
|
#define <xsl:value-of select="$NameSpace"/><xsl:text>_PARAMS_H</xsl:text>
|
||||||
|
|
||||||
|
#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 <xsl:value-of select="$NameSpace"/>
|
||||||
|
{
|
||||||
|
|
||||||
|
//**************************************************************************************************
|
||||||
|
// Enumerations
|
||||||
|
//**************************************************************************************************
|
||||||
|
<xsl:apply-templates select="/RegisterDescription/Enumeration" mode="DefiningEnums"/>
|
||||||
|
|
||||||
|
//**************************************************************************************************
|
||||||
|
// Parameter class
|
||||||
|
//**************************************************************************************************
|
||||||
|
<xsl:variable name="Class">
|
||||||
|
<xsl:text>C</xsl:text><xsl:value-of select="/RegisterDescription/@ModelName"/><xsl:text>_Params</xsl:text>
|
||||||
|
</xsl:variable>
|
||||||
|
|
||||||
|
//! <xsl:value-of select="/RegisterDescription/@ToolTip"/>
|
||||||
|
class <xsl:value-of select="$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
|
||||||
|
<xsl:value-of select="$Class"/>(void);
|
||||||
|
|
||||||
|
//! Destructor
|
||||||
|
~<xsl:value-of select="$Class"/>(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:
|
||||||
|
<xsl:apply-templates select="/RegisterDescription/*[ @ExposeStatic='Yes' or ( (/RegisterDescription/Category/pFeature=@Name and name()!='Category') and not(@ExposeStatic='No') ) ]" mode="ReferenceDeclaration"/>
|
||||||
|
|
||||||
|
private:
|
||||||
|
//! \cond HIDE_CLASS_METHODS
|
||||||
|
|
||||||
|
//! not implemented copy constructor
|
||||||
|
<xsl:value-of select="$Class"/>(<xsl:value-of select="$Class"/>&);
|
||||||
|
|
||||||
|
//! not implemented assignment operator
|
||||||
|
<xsl:value-of select="$Class"/>& operator=(<xsl:value-of select="$Class"/>&);
|
||||||
|
|
||||||
|
//! \endcond
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
//**************************************************************************************************
|
||||||
|
// Parameter class implementation
|
||||||
|
//**************************************************************************************************
|
||||||
|
|
||||||
|
//! \cond HIDE_CLASS_METHODS
|
||||||
|
|
||||||
|
inline <xsl:value-of select="$Class"/>::<xsl:value-of select="$Class"/>(void)
|
||||||
|
<xsl:apply-templates select="/RegisterDescription/*[ @ExposeStatic='Yes' or ( (/RegisterDescription/Category/pFeature=@Name and name()!='Category') and not(@ExposeStatic='No') ) ]" mode="ReferenceCreation"/>
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
inline <xsl:value-of select="$Class"/>::~<xsl:value-of select="$Class"/>(void)
|
||||||
|
{
|
||||||
|
<xsl:apply-templates select="/RegisterDescription/*[ @ExposeStatic='Yes' or ( (/RegisterDescription/Category/pFeature=@Name and name()!='Category') and not(@ExposeStatic='No') ) ]" mode="ReferenceDeletion"/>
|
||||||
|
}
|
||||||
|
|
||||||
|
inline void <xsl:value-of select="$Class"/>::_Initialize(GenApi::INodeMap* _Ptr)
|
||||||
|
{
|
||||||
|
<xsl:apply-templates select="/RegisterDescription/*[ @ExposeStatic='Yes' or ( (/RegisterDescription/Category/pFeature=@Name and name()!='Category') and not(@ExposeStatic='No') ) ]" mode="ReferenceInitialization"/>
|
||||||
|
}
|
||||||
|
|
||||||
|
inline const char* <xsl:value-of select="$Class"/>::_GetVendorName(void)
|
||||||
|
{
|
||||||
|
return "<xsl:value-of select="RegisterDescription/@VendorName"/>";
|
||||||
|
}
|
||||||
|
|
||||||
|
inline const char* <xsl:value-of select="$Class"/>::_GetModelName(void)
|
||||||
|
{
|
||||||
|
return "<xsl:value-of select="RegisterDescription/@ModelName"/>";
|
||||||
|
}
|
||||||
|
|
||||||
|
//! \endcond
|
||||||
|
|
||||||
|
} // namespace <xsl:value-of select="$NameSpace"/>
|
||||||
|
|
||||||
|
#endif // <xsl:value-of select="$NameSpace"/><xsl:text>_PARAMS_H</xsl:text>
|
||||||
|
|
||||||
|
<xsl:text>
|
||||||
|
</xsl:text>
|
||||||
|
|
||||||
|
</xsl:template>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
<!-- DefiningEnums -->
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
|
||||||
|
<xsl:template match="Enumeration" mode="DefiningEnums">
|
||||||
|
//! Valid values for <xsl:value-of select="@Name"/>
|
||||||
|
enum <xsl:value-of select="@Name"/>Enums
|
||||||
|
{
|
||||||
|
<xsl:apply-templates select="./pEnumEntry" mode="InsideDefiningEnums"/>
|
||||||
|
};
|
||||||
|
</xsl:template>
|
||||||
|
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
<!-- InsideDefiningEnums -->
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
|
||||||
|
<xsl:template match="pEnumEntry" mode="InsideDefiningEnums">
|
||||||
|
<xsl:variable name="NodeName" select="string()"/>
|
||||||
|
<xsl:variable name="Separator">
|
||||||
|
<xsl:choose>
|
||||||
|
<xsl:when test="position()!=last()">
|
||||||
|
<xsl:text>, </xsl:text>
|
||||||
|
</xsl:when>
|
||||||
|
<xsl:otherwise>
|
||||||
|
<xsl:text> </xsl:text>
|
||||||
|
</xsl:otherwise>
|
||||||
|
</xsl:choose>
|
||||||
|
</xsl:variable>
|
||||||
|
<xsl:value-of select="../@Name"/>_<xsl:value-of select="../../EnumEntry[@Name=$NodeName]/Symbolic"/><xsl:value-of select="$Separator"/> //!<<xsl:value-of select="../../EnumEntry[@Name=$NodeName]/ToolTip"/><xsl:text>
		</xsl:text>
|
||||||
|
</xsl:template>
|
||||||
|
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
<!-- ReferenceDeclaration -->
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
|
||||||
|
<xsl:template match="*" mode="ReferenceDeclaration">
|
||||||
|
<xsl:variable name="Feature" select="@Name"/>
|
||||||
|
<xsl:variable name="NodeType" select="name()"/>
|
||||||
|
|
||||||
|
<xsl:choose>
|
||||||
|
<xsl:when test="/RegisterDescription/Category[pFeature=$Feature]">
|
||||||
|
//! \name <xsl:value-of select="/RegisterDescription/Category[pFeature=$Feature]/@Name"/> - <xsl:value-of select="/RegisterDescription/Category[pFeature=$Feature]/ToolTip"/>
|
||||||
|
</xsl:when>
|
||||||
|
<xsl:otherwise>
|
||||||
|
//! \name Miscellaneous Features
|
||||||
|
</xsl:otherwise>
|
||||||
|
</xsl:choose>
|
||||||
|
//@{
|
||||||
|
/*!
|
||||||
|
\brief <xsl:value-of select="/RegisterDescription/*[@Name=$Feature]/ToolTip"/>
|
||||||
|
<xsl:text>

	</xsl:text>
|
||||||
|
<xsl:value-of select="/RegisterDescription/*[@Name=$Feature]/Description"/>
|
||||||
|
<xsl:text>
	</xsl:text>
|
||||||
|
<xsl:choose>
|
||||||
|
<xsl:when test="/RegisterDescription/*[@Name=$Feature]/Visibility">
|
||||||
|
\b Visibility = <xsl:value-of select="/RegisterDescription/*[@Name=$Feature]/Visibility"/>
|
||||||
|
</xsl:when>
|
||||||
|
<xsl:otherwise>
|
||||||
|
\b Visibility = Beginner
|
||||||
|
</xsl:otherwise>
|
||||||
|
</xsl:choose><xsl:text>
	</xsl:text>
|
||||||
|
<xsl:if test="/RegisterDescription/*[@Name=$Feature]/pSelecting">
|
||||||
|
\b Selected by : <xsl:for-each select="/RegisterDescription/*[@Name=$Feature]/pSelecting">
|
||||||
|
<xsl:value-of select="node()"/>
|
||||||
|
<xsl:if test="position()!=last()">, </xsl:if>
|
||||||
|
</xsl:for-each>
|
||||||
|
<xsl:text>
	</xsl:text>
|
||||||
|
</xsl:if>
|
||||||
|
*/
|
||||||
|
<xsl:if test="/RegisterDescription/*[@Name=$Feature]/IsDeprecated='Yes'">
|
||||||
|
# pragma deprecated( <xsl:value-of select="$Feature"/> )
|
||||||
|
# pragma warning(push)
|
||||||
|
# pragma warning(disable: 4995) // name has been marked as deprecated
|
||||||
|
</xsl:if>
|
||||||
|
<xsl:choose>
|
||||||
|
<xsl:when test="$NodeType = 'Enumeration'">
|
||||||
|
<xsl:text>GenApi::</xsl:text>
|
||||||
|
<xsl:value-of select="document('NodeTypes.xml')/NodeTypes/Node/CppInterface[../@Name=$NodeType]"/><xsl:text>T<</xsl:text>
|
||||||
|
<xsl:value-of select="$Feature"/>Enums <xsl:text>></xsl:text>
|
||||||
|
</xsl:when>
|
||||||
|
<xsl:otherwise>
|
||||||
|
<xsl:text>GenApi::</xsl:text>
|
||||||
|
<xsl:value-of select="document('NodeTypes.xml')/NodeTypes/Node/CppInterface[../@Name=$NodeType]"/>
|
||||||
|
</xsl:otherwise>
|
||||||
|
</xsl:choose>
|
||||||
|
<xsl:text> &</xsl:text>
|
||||||
|
<xsl:value-of select="$Feature"/>;
|
||||||
|
<xsl:if test="/RegisterDescription/*[@Name=$Feature]/IsDeprecated='Yes'">
|
||||||
|
# pragma warning(pop)
|
||||||
|
</xsl:if>
|
||||||
|
//@}
|
||||||
|
|
||||||
|
</xsl:template>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
<!-- ReferenceCreation -->
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
|
||||||
|
<xsl:template match="*" mode="ReferenceCreation">
|
||||||
|
<xsl:variable name="Feature" select="@Name"/>
|
||||||
|
<xsl:variable name="NodeType" select="name()"/>
|
||||||
|
|
||||||
|
<xsl:variable name="Separator">
|
||||||
|
<xsl:choose>
|
||||||
|
<xsl:when test="position()=1">
|
||||||
|
<xsl:text>: </xsl:text>
|
||||||
|
</xsl:when>
|
||||||
|
<xsl:otherwise>
|
||||||
|
<xsl:text>, </xsl:text>
|
||||||
|
</xsl:otherwise>
|
||||||
|
</xsl:choose>
|
||||||
|
</xsl:variable>
|
||||||
|
<xsl:if test="./IsDeprecated='Yes'">
|
||||||
|
# pragma warning(push)
|
||||||
|
# pragma warning(disable: 4995) // name has been marked as deprecated
|
||||||
|
</xsl:if>
|
||||||
|
<xsl:choose>
|
||||||
|
<xsl:when test="$NodeType = 'Enumeration'">
|
||||||
|
<xsl:value-of select="$Separator"/><xsl:value-of select="$Feature"/>( *new GenApi::<xsl:value-of select="document('NodeTypes.xml')/NodeTypes/Node/CppReference[../@Name=$NodeType]"/><<xsl:value-of select="$Feature"/>Enums>() )
|
||||||
|
</xsl:when>
|
||||||
|
<xsl:otherwise>
|
||||||
|
<xsl:value-of select="$Separator"/><xsl:value-of select="$Feature"/>( *new GenApi::<xsl:value-of select="document('NodeTypes.xml')/NodeTypes/Node/CppReference[../@Name=$NodeType]"/>() )
|
||||||
|
</xsl:otherwise>
|
||||||
|
</xsl:choose>
|
||||||
|
<xsl:if test="./IsDeprecated='Yes'">
|
||||||
|
# pragma warning(pop)
|
||||||
|
</xsl:if>
|
||||||
|
</xsl:template>
|
||||||
|
|
||||||
|
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
<!-- ReferenceDeletion -->
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
|
||||||
|
<xsl:template match="*" mode="ReferenceDeletion">
|
||||||
|
<xsl:variable name="Feature" select="@Name"/>
|
||||||
|
<xsl:variable name="NodeType" select="name()"/>
|
||||||
|
<xsl:if test="./IsDeprecated='Yes'">
|
||||||
|
# pragma warning(push)
|
||||||
|
# pragma warning(disable: 4995) // name has been marked as deprecated
|
||||||
|
</xsl:if>
|
||||||
|
<xsl:choose>
|
||||||
|
<xsl:when test="$NodeType = 'Enumeration'">
|
||||||
|
<xsl:text>delete static_cast < GenApi::</xsl:text><xsl:value-of select="document('NodeTypes.xml')/NodeTypes/Node/CppReference[../@Name=$NodeType]"/><<xsl:value-of select="$Feature"/>Enums> *> (&<xsl:value-of select="$Feature"/> );
|
||||||
|
</xsl:when>
|
||||||
|
<xsl:otherwise>
|
||||||
|
<xsl:text>delete static_cast < GenApi::</xsl:text><xsl:value-of select="document('NodeTypes.xml')/NodeTypes/Node/CppReference[../@Name=$NodeType]"/>*> (&<xsl:value-of select="$Feature"/> );
|
||||||
|
</xsl:otherwise>
|
||||||
|
</xsl:choose>
|
||||||
|
<xsl:if test="./IsDeprecated='Yes'">
|
||||||
|
# pragma warning(pop)
|
||||||
|
</xsl:if>
|
||||||
|
</xsl:template>
|
||||||
|
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
<!-- ReferenceInitialization -->
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
|
||||||
|
<xsl:template match="*" mode="ReferenceInitialization">
|
||||||
|
<xsl:variable name="Feature" select="@Name"/>
|
||||||
|
<xsl:variable name="NodeType" select="name()"/>
|
||||||
|
<xsl:if test="./IsDeprecated='Yes'">
|
||||||
|
# pragma warning(push)
|
||||||
|
# pragma warning(disable: 4995) // name has been marked as deprecated
|
||||||
|
</xsl:if>
|
||||||
|
<xsl:choose>
|
||||||
|
<xsl:when test="$NodeType = 'Enumeration'">
|
||||||
|
<xsl:text>static_cast<GenApi::</xsl:text><xsl:value-of select="document('NodeTypes.xml')/NodeTypes/Node/CppReference[../@Name=$NodeType]"/><<xsl:value-of select="$Feature"/>Enums> *> (&<xsl:value-of select="$Feature"/> )<xsl:text>->SetReference(_Ptr->GetNode("</xsl:text><xsl:value-of select="$Feature"/>"));
|
||||||
|
</xsl:when>
|
||||||
|
<xsl:otherwise>
|
||||||
|
<xsl:text>static_cast<GenApi::</xsl:text><xsl:value-of select="document('NodeTypes.xml')/NodeTypes/Node/CppReference[../@Name=$NodeType]"/>*> (&<xsl:value-of select="$Feature"/> )<xsl:text>->SetReference(_Ptr->GetNode("</xsl:text><xsl:value-of select="$Feature"/>"));
|
||||||
|
</xsl:otherwise>
|
||||||
|
</xsl:choose>
|
||||||
|
|
||||||
|
<xsl:if test="$NodeType = 'Enumeration'">
|
||||||
|
<xsl:text>static_cast<GenApi::</xsl:text><xsl:value-of select="document('NodeTypes.xml')/NodeTypes/Node/CppReference[../@Name=$NodeType]"/><<xsl:value-of select="$Feature"/>Enums> *> (&<xsl:value-of select="$Feature"/> )<xsl:text>->SetNumEnums(</xsl:text><xsl:value-of select="count(/RegisterDescription/*[@Name=$Feature]/pEnumEntry)"/>);<xsl:text>
	</xsl:text>
|
||||||
|
<xsl:apply-templates select="/RegisterDescription/*[@Name=$Feature]/pEnumEntry" mode="EnumInitialization">
|
||||||
|
<xsl:with-param name="EnumName" select="$Feature"/>
|
||||||
|
<xsl:with-param name="NodeType" select="$NodeType"/>
|
||||||
|
</xsl:apply-templates>
|
||||||
|
</xsl:if>
|
||||||
|
<xsl:if test="./IsDeprecated='Yes'">
|
||||||
|
# pragma warning(pop)
|
||||||
|
</xsl:if>
|
||||||
|
</xsl:template>
|
||||||
|
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
<!-- EnumInitialization -->
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
|
||||||
|
<xsl:template match="*" mode="EnumInitialization">
|
||||||
|
<xsl:param name="EnumName"/>
|
||||||
|
<xsl:variable name="FeatureName" select="string()"/>
|
||||||
|
<xsl:apply-templates select="/RegisterDescription/*[@Name=$FeatureName]" mode="EnumEntryInitialization">
|
||||||
|
<xsl:with-param name="EnumName" select="$EnumName"/>
|
||||||
|
</xsl:apply-templates>
|
||||||
|
</xsl:template>
|
||||||
|
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
<!-- EnumEntryInitialization -->
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
|
||||||
|
<xsl:template match="*" mode="EnumEntryInitialization">
|
||||||
|
<xsl:param name="EnumName"/>
|
||||||
|
<xsl:param name="NodeType" />
|
||||||
|
<xsl:text>static_cast<GenApi::CEnumerationTRef</xsl:text><<xsl:value-of select="$EnumName"/>Enums> *> (&<xsl:value-of select="$EnumName"/> )<xsl:text>->SetEnumReference( </xsl:text><xsl:value-of select="$EnumName"/>_<xsl:value-of select="./Symbolic"/>, "<xsl:value-of select="./Symbolic"/>" );<xsl:text>		</xsl:text>
|
||||||
|
</xsl:template>
|
||||||
|
|
||||||
|
</xsl:stylesheet>
|
83
camera_driver/lib/GenICam/xml/GenApi/GenApi_Ptr_h.xsl
Normal file
83
camera_driver/lib/GenICam/xml/GenApi/GenApi_Ptr_h.xsl
Normal file
@ -0,0 +1,83 @@
|
|||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<!-- ***************************************************************************
|
||||||
|
* (c) 2004-2008 by Basler Vision Technologies
|
||||||
|
* Section: Vision Components
|
||||||
|
* Project: GenApi
|
||||||
|
* Author: Urs Helmig
|
||||||
|
* $Header$
|
||||||
|
*
|
||||||
|
* License: This file is published under the license of the EMVA GenICam Standard Group.
|
||||||
|
* A text file describing the legal terms is included in your installation as 'GenICam_license.pdf'.
|
||||||
|
* If for some reason you are missing this file please contact the EMVA or visit the website
|
||||||
|
* (http://www.genicam.org) for a full copy.
|
||||||
|
*
|
||||||
|
* THIS SOFTWARE IS PROVIDED BY THE EMVA GENICAM STANDARD GROUP "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 EMVA GENICAM STANDARD GROUP
|
||||||
|
* 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.
|
||||||
|
******************************************************************************** -->
|
||||||
|
<xsl:stylesheet version="1.0" xmlns:my_v1_0="http://www.genicam.org/GenApi/Version_1_0" xmlns:my_v1_1="http://www.genicam.org/GenApi/Version_1_1" xmlns:xsl="http://www.w3.org/1999/XSL/Transform">
|
||||||
|
<xsl:output method="text" encoding="UTF-8" media-type="text/plain"/>
|
||||||
|
|
||||||
|
<xsl:param name="HeaderFileName"><xsl:value-of select="/RegisterDescription/@ModelName"/><xsl:text>Params.h</xsl:text></xsl:param>
|
||||||
|
|
||||||
|
<xsl:template match="/">
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
<!-- Main body -->
|
||||||
|
<!-- =========================================================================== -->
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
// (c) 2004-2008 by Basler Vision Technologies
|
||||||
|
// Section: Vision Components
|
||||||
|
// Project: GenApi
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
/*!
|
||||||
|
\file
|
||||||
|
\brief <xsl:value-of select="/RegisterDescription/@ToolTip"/>
|
||||||
|
*/
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
// This file is generated automatically
|
||||||
|
// Do not modify!
|
||||||
|
//-----------------------------------------------------------------------------
|
||||||
|
<xsl:variable name="NameSpace">
|
||||||
|
<xsl:value-of select="/RegisterDescription/@VendorName"/>_<xsl:value-of select="/RegisterDescription/@ModelName"/>
|
||||||
|
</xsl:variable>
|
||||||
|
|
||||||
|
#ifndef <xsl:value-of select="$NameSpace"/><xsl:text>_PTR_H</xsl:text>
|
||||||
|
#define <xsl:value-of select="$NameSpace"/><xsl:text>_PTR_H</xsl:text>
|
||||||
|
|
||||||
|
#include <GenApi/NodeMapRef.h>
|
||||||
|
#include "<xsl:value-of select="$HeaderFileName"/>"
|
||||||
|
|
||||||
|
//! The namespace containing the device's control interface and related enumeration types
|
||||||
|
namespace <xsl:value-of select="$NameSpace"/>
|
||||||
|
{
|
||||||
|
//**************************************************************************************************
|
||||||
|
// Access class
|
||||||
|
//**************************************************************************************************
|
||||||
|
//! <xsl:value-of select="/RegisterDescription/@ToolTip"/>
|
||||||
|
class C<xsl:value-of select="/RegisterDescription/@ModelName"/>
|
||||||
|
: public GenApi::CNodeMapRefT<<xsl:value-of select="$NameSpace"/>::C<xsl:value-of select="/RegisterDescription/@ModelName"/>_Params>
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
//! Constructor
|
||||||
|
C<xsl:value-of select="/RegisterDescription/@ModelName"/>(GenICam::gcstring DeviceName = "Device") : GenApi::CNodeMapRefT<<xsl:value-of select="$NameSpace"/>::C<xsl:value-of select="/RegisterDescription/@ModelName"/>_Params>(DeviceName)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
} // namespace <xsl:value-of select="$NameSpace"/>
|
||||||
|
|
||||||
|
#endif // <xsl:value-of select="$NameSpace"/><xsl:text>_PTR_H</xsl:text>
|
||||||
|
<xsl:text>
|
||||||
|
</xsl:text>
|
||||||
|
|
||||||
|
</xsl:template>
|
||||||
|
</xsl:stylesheet>
|
131
camera_driver/lib/GenICam/xml/GenApi/NodeTypes.xml
Normal file
131
camera_driver/lib/GenICam/xml/GenApi/NodeTypes.xml
Normal file
@ -0,0 +1,131 @@
|
|||||||
|
<?xml version="1.0" encoding="utf-8"?>
|
||||||
|
<!-- edited with XMLSpy v2005 U (http://www.xmlspy.com) by Heike Skrzynski-Fox (Basler AG) -->
|
||||||
|
<!-- ***************************************************************************
|
||||||
|
* (c) 2004 by Basler Vision Technologies
|
||||||
|
* Section: Vision Components
|
||||||
|
* Project: GenApi
|
||||||
|
* Author: Fritz Dierks
|
||||||
|
* $Header$
|
||||||
|
******************************************************************************** -->
|
||||||
|
<NodeTypes xmlns:xsi="http://www.w3.org/2001/XMLSchema-instance" xsi:noNamespaceSchemaLocation="NodeTypes.xsd">
|
||||||
|
<Node Name="Node">
|
||||||
|
<CppClass>CValueNode</CppClass>
|
||||||
|
<CppInterface>IValue</CppInterface>
|
||||||
|
<CppReference>CValueRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="Category">
|
||||||
|
<CppClass>CCategory</CppClass>
|
||||||
|
<CppInterface>ICategory</CppInterface>
|
||||||
|
<CppReference>CCategoryRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="Integer">
|
||||||
|
<CppClass>CInteger</CppClass>
|
||||||
|
<CppInterface>IInteger</CppInterface>
|
||||||
|
<CppReference>CIntegerRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="Enumeration">
|
||||||
|
<CppClass>CEnumeration</CppClass>
|
||||||
|
<CppInterface>IEnumeration</CppInterface>
|
||||||
|
<CppReference>CEnumerationTRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="EnumEntry">
|
||||||
|
<CppClass>CEnumEntry</CppClass>
|
||||||
|
<CppInterface>IEnumEntry</CppInterface>
|
||||||
|
<CppReference>CEnumEntryRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="MaskedIntReg">
|
||||||
|
<CppClass>CMaskedIntReg</CppClass>
|
||||||
|
<CppInterface>IInteger</CppInterface>
|
||||||
|
<CppReference>CIntegerRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="Register">
|
||||||
|
<CppClass>CRegister</CppClass>
|
||||||
|
<CppInterface>IRegister</CppInterface>
|
||||||
|
<CppReference>CRegisterRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="IntReg">
|
||||||
|
<CppClass>CIntReg</CppClass>
|
||||||
|
<CppInterface>IInteger</CppInterface>
|
||||||
|
<CppReference>CIntegerRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="Float">
|
||||||
|
<CppClass>CFloat</CppClass>
|
||||||
|
<CppInterface>IFloat</CppInterface>
|
||||||
|
<CppReference>CFloatRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="FloatReg">
|
||||||
|
<CppClass>CFltReg</CppClass>
|
||||||
|
<CppInterface>IFloat</CppInterface>
|
||||||
|
<CppReference>CFloatRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="SwissKnife">
|
||||||
|
<CppClass>CSwissKnife</CppClass>
|
||||||
|
<CppInterface>IFloat</CppInterface>
|
||||||
|
<CppReference>CFloatRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="IntSwissKnife">
|
||||||
|
<CppClass>CIntSwissKnife</CppClass>
|
||||||
|
<CppInterface>IInteger</CppInterface>
|
||||||
|
<CppReference>CIntegerRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="IntKey">
|
||||||
|
<CppClass>CIntKey</CppClass>
|
||||||
|
<CppInterface>IInteger</CppInterface>
|
||||||
|
<CppReference>CIntegerRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="TextDesc">
|
||||||
|
<CppClass>CTxtKey</CppClass>
|
||||||
|
<CppInterface>IString</CppInterface>
|
||||||
|
<CppReference>CStringRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="Port">
|
||||||
|
<CppClass>CPort</CppClass>
|
||||||
|
<CppInterface>IPort</CppInterface>
|
||||||
|
<CppReference>CPortRecorderRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="ConfRom">
|
||||||
|
<CppClass>CIEEE1212Parser</CppClass>
|
||||||
|
<CppInterface>IRegister</CppInterface>
|
||||||
|
<CppReference>CRegisterRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="AdvFeatureLock">
|
||||||
|
<CppClass>CDcamAccessCtrlReg</CppClass>
|
||||||
|
<CppInterface>IInteger</CppInterface>
|
||||||
|
<CppReference>CIntegerRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="SmartFeature">
|
||||||
|
<CppClass>CSmartFeature</CppClass>
|
||||||
|
<CppInterface>IInteger</CppInterface>
|
||||||
|
<CppReference>CIntegerRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="String">
|
||||||
|
<CppClass>CStringNode</CppClass>
|
||||||
|
<CppInterface>IString</CppInterface>
|
||||||
|
<CppReference>CStringRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="StringReg">
|
||||||
|
<CppClass>CStringRegister</CppClass>
|
||||||
|
<CppInterface>IString</CppInterface>
|
||||||
|
<CppReference>CStringRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="Boolean">
|
||||||
|
<CppClass>CBoolean</CppClass>
|
||||||
|
<CppInterface>IBoolean</CppInterface>
|
||||||
|
<CppReference>CBooleanRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="Command">
|
||||||
|
<CppClass>CCommand</CppClass>
|
||||||
|
<CppInterface>ICommand</CppInterface>
|
||||||
|
<CppReference>CCommandRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="Converter">
|
||||||
|
<CppClass>CConverter</CppClass>
|
||||||
|
<CppInterface>IFloat</CppInterface>
|
||||||
|
<CppReference>CFloatRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
<Node Name="IntConverter">
|
||||||
|
<CppClass>CIntConverter</CppClass>
|
||||||
|
<CppInterface>IInteger</CppInterface>
|
||||||
|
<CppReference>CIntegerRef</CppReference>
|
||||||
|
</Node>
|
||||||
|
</NodeTypes>
|
28
camera_driver/lib/GenICam/xml/GenApi/NodeTypes.xsd
Normal file
28
camera_driver/lib/GenICam/xml/GenApi/NodeTypes.xsd
Normal file
@ -0,0 +1,28 @@
|
|||||||
|
<?xml version="1.0" encoding="UTF-8"?>
|
||||||
|
<!--W3C Schema generated by XMLSPY v2004 rel. 4 U (http://www.xmlspy.com)-->
|
||||||
|
<xs:schema xmlns:xs="http://www.w3.org/2001/XMLSchema" elementFormDefault="qualified">
|
||||||
|
<xs:element name="CppClass" type="xs:token"/>
|
||||||
|
<xs:element name="CppInterface" type="xs:token"/>
|
||||||
|
<xs:element name="CppReference" type="xs:token"/>
|
||||||
|
<xs:element name="Node">
|
||||||
|
<xs:complexType>
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element ref="CppClass"/>
|
||||||
|
<xs:element ref="CppInterface"/>
|
||||||
|
<xs:element ref="CppReference"/>
|
||||||
|
</xs:sequence>
|
||||||
|
<xs:attribute name="Name" use="required"/>
|
||||||
|
</xs:complexType>
|
||||||
|
<xs:unique name="NodeKey">
|
||||||
|
<xs:selector xpath="./Node"/>
|
||||||
|
<xs:field xpath="@Name"/>
|
||||||
|
</xs:unique>
|
||||||
|
</xs:element>
|
||||||
|
<xs:element name="NodeTypes">
|
||||||
|
<xs:complexType>
|
||||||
|
<xs:sequence>
|
||||||
|
<xs:element ref="Node" maxOccurs="unbounded"/>
|
||||||
|
</xs:sequence>
|
||||||
|
</xs:complexType>
|
||||||
|
</xs:element>
|
||||||
|
</xs:schema>
|
BIN
camera_driver/lib/Qt/libQt5Core.so.5.5.1
Normal file
BIN
camera_driver/lib/Qt/libQt5Core.so.5.5.1
Normal file
Binary file not shown.
BIN
camera_driver/lib/Qt/libQt5DBus.so.5.5.1
Normal file
BIN
camera_driver/lib/Qt/libQt5DBus.so.5.5.1
Normal file
Binary file not shown.
BIN
camera_driver/lib/Qt/libQt5Gui.so.5.5.1
Normal file
BIN
camera_driver/lib/Qt/libQt5Gui.so.5.5.1
Normal file
Binary file not shown.
BIN
camera_driver/lib/Qt/libQt5Network.so.5.5.1
Normal file
BIN
camera_driver/lib/Qt/libQt5Network.so.5.5.1
Normal file
Binary file not shown.
BIN
camera_driver/lib/Qt/libQt5Xml.so.5.5.1
Normal file
BIN
camera_driver/lib/Qt/libQt5Xml.so.5.5.1
Normal file
Binary file not shown.
BIN
camera_driver/lib/libImageConvert.so
Normal file
BIN
camera_driver/lib/libImageConvert.so
Normal file
Binary file not shown.
BIN
camera_driver/lib/libMVSDK.so.2.1.0.194984
Normal file
BIN
camera_driver/lib/libMVSDK.so.2.1.0.194984
Normal file
Binary file not shown.
BIN
camera_driver/lib/libMVSDKGuiQt.so
Normal file
BIN
camera_driver/lib/libMVSDKGuiQt.so
Normal file
Binary file not shown.
BIN
camera_driver/lib/libVideoRender.so
Normal file
BIN
camera_driver/lib/libVideoRender.so
Normal file
Binary file not shown.
BIN
camera_driver/lib/liblog4cpp.so
Normal file
BIN
camera_driver/lib/liblog4cpp.so
Normal file
Binary file not shown.
146
capture.py
Normal file
146
capture.py
Normal file
@ -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 接收 回调,把结果保存下来
|
1244
cloud_3d_detect.py
Normal file
1244
cloud_3d_detect.py
Normal file
File diff suppressed because it is too large
Load Diff
73
config.py
Normal file
73
config.py
Normal file
@ -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\\"
|
0
dialog-analysis.log
Normal file
0
dialog-analysis.log
Normal file
202
it.py
Normal file
202
it.py
Normal file
@ -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)
|
56
lidar_driver/CMakeLists.txt
Normal file
56
lidar_driver/CMakeLists.txt
Normal file
@ -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
|
||||||
|
)
|
||||||
|
|
||||||
|
|
30
lidar_driver/README.MD
Normal file
30
lidar_driver/README.MD
Normal file
@ -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
|
7
lidar_driver/build.sh
Normal file
7
lidar_driver/build.sh
Normal file
@ -0,0 +1,7 @@
|
|||||||
|
#!/usr/bin/env bash
|
||||||
|
rm -rf build
|
||||||
|
mkdir build
|
||||||
|
cd build
|
||||||
|
cmake ..
|
||||||
|
make
|
||||||
|
cp liblivox_sdk_wrapper.so ../
|
24
lidar_driver/cmake/cmakebase.cmake
Normal file
24
lidar_driver/cmake/cmakebase.cmake
Normal file
@ -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)
|
||||||
|
|
96
lidar_driver/cmake/project.cmake
Normal file
96
lidar_driver/cmake/project.cmake
Normal file
@ -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)
|
5
lidar_driver/cmake/ss928.cmake
Normal file
5
lidar_driver/cmake/ss928.cmake
Normal file
@ -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})
|
72
lidar_driver/include/Livox/comm/comm_port.h
Normal file
72
lidar_driver/include/Livox/comm/comm_port.h
Normal file
@ -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 <stdint.h>
|
||||||
|
#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_
|
82
lidar_driver/include/Livox/comm/protocol.h
Normal file
82
lidar_driver/include/Livox/comm/protocol.h
Normal file
@ -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 <stdint.h>
|
||||||
|
|
||||||
|
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_
|
49
lidar_driver/include/Livox/config.h
Normal file
49
lidar_driver/include/Livox/config.h
Normal file
@ -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 <sys/epoll.h>
|
||||||
|
#include <sys/time.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#define HAVE_EPOLL 1
|
||||||
|
#elif defined(_WIN32)
|
||||||
|
#include <winsock2.h>
|
||||||
|
#define HAVE_SELECT 1
|
||||||
|
#elif defined(__APPLE__) || defined(__FreeBSD__) || defined(__OpenBSD__) || defined (__NetBSD__)
|
||||||
|
#include <sys/event.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
#define HAVE_KQUEUE 1
|
||||||
|
#else
|
||||||
|
#include <sys/poll.h>
|
||||||
|
#define HAVE_POLL 1
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#endif // CONFIG_H_
|
||||||
|
|
||||||
|
|
855
lidar_driver/include/Livox/livox_def.h
Normal file
855
lidar_driver/include/Livox/livox_def.h
Normal file
@ -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 <stdint.h>
|
||||||
|
|
||||||
|
#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_
|
999
lidar_driver/include/Livox/livox_sdk.h
Normal file
999
lidar_driver/include/Livox/livox_sdk.h
Normal file
@ -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 <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#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_
|
79
lidar_driver/include/Livox/third_party/FastCRC/FastCRC.h
vendored
Normal file
79
lidar_driver/include/Livox/third_party/FastCRC/FastCRC.h
vendored
Normal file
@ -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 <stdint.h>
|
||||||
|
|
||||||
|
|
||||||
|
// ================= 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_
|
||||||
|
|
823
lidar_driver/include/Livox/third_party/cmdline/cmdline.h
vendored
Normal file
823
lidar_driver/include/Livox/third_party/cmdline/cmdline.h
vendored
Normal file
@ -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 <organization> 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 <copyright holder> ''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 <copyright holder> 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 <iostream>
|
||||||
|
#include <sstream>
|
||||||
|
#include <vector>
|
||||||
|
#include <map>
|
||||||
|
#include <string>
|
||||||
|
#include <stdexcept>
|
||||||
|
#include <typeinfo>
|
||||||
|
#include <cstring>
|
||||||
|
#include <algorithm>
|
||||||
|
#if defined(_MSC_VER)
|
||||||
|
#include <windows.h>
|
||||||
|
#include <dbghelp.h>
|
||||||
|
#undef max
|
||||||
|
#pragma comment(lib, "dbghelp.lib")
|
||||||
|
#elif defined(__clang__) || defined(__GNUC__)
|
||||||
|
#include <cxxabi.h>
|
||||||
|
#endif
|
||||||
|
#include <cstdlib>
|
||||||
|
|
||||||
|
namespace cmdline{
|
||||||
|
|
||||||
|
namespace detail{
|
||||||
|
|
||||||
|
template <typename Target, typename Source, bool Same>
|
||||||
|
class lexical_cast_t{
|
||||||
|
public:
|
||||||
|
static Target cast(const Source &arg){
|
||||||
|
Target ret;
|
||||||
|
std::stringstream ss;
|
||||||
|
if (!(ss<<arg && ss>>ret && ss.eof()))
|
||||||
|
throw std::bad_cast();
|
||||||
|
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename Target, typename Source>
|
||||||
|
class lexical_cast_t<Target, Source, true>{
|
||||||
|
public:
|
||||||
|
static Target cast(const Source &arg){
|
||||||
|
return arg;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename Source>
|
||||||
|
class lexical_cast_t<std::string, Source, false>{
|
||||||
|
public:
|
||||||
|
static std::string cast(const Source &arg){
|
||||||
|
std::ostringstream ss;
|
||||||
|
ss<<arg;
|
||||||
|
return ss.str();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename Target>
|
||||||
|
class lexical_cast_t<Target, std::string, false>{
|
||||||
|
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 <typename T1, typename T2>
|
||||||
|
struct is_same {
|
||||||
|
static const bool value = false;
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
struct is_same<T, T>{
|
||||||
|
static const bool value = true;
|
||||||
|
};
|
||||||
|
|
||||||
|
template<typename Target, typename Source>
|
||||||
|
Target lexical_cast(const Source &arg)
|
||||||
|
{
|
||||||
|
return lexical_cast_t<Target, Source, detail::is_same<Target, Source>::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 <class T>
|
||||||
|
std::string readable_typename()
|
||||||
|
{
|
||||||
|
return demangle(typeid(T).name());
|
||||||
|
}
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
std::string default_value(T def)
|
||||||
|
{
|
||||||
|
return detail::lexical_cast<std::string>(def);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <>
|
||||||
|
inline std::string readable_typename<std::string>()
|
||||||
|
{
|
||||||
|
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 <class T>
|
||||||
|
struct default_reader{
|
||||||
|
T operator()(const std::string &str){
|
||||||
|
return detail::lexical_cast<T>(str);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
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<T>()(s);
|
||||||
|
if (!(ret>=low && ret<=high)) throw cmdline::cmdline_error("range_error");
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
private:
|
||||||
|
T low, high;
|
||||||
|
};
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
range_reader<T> range(const T &low, const T &high)
|
||||||
|
{
|
||||||
|
return range_reader<T>(low, high);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
struct oneof_reader{
|
||||||
|
T operator()(const std::string &s){
|
||||||
|
T ret=default_reader<T>()(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<T> alt;
|
||||||
|
};
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
oneof_reader<T> oneof(T a1)
|
||||||
|
{
|
||||||
|
oneof_reader<T> ret;
|
||||||
|
ret.add(a1);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
oneof_reader<T> oneof(T a1, T a2)
|
||||||
|
{
|
||||||
|
oneof_reader<T> ret;
|
||||||
|
ret.add(a1);
|
||||||
|
ret.add(a2);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
oneof_reader<T> oneof(T a1, T a2, T a3)
|
||||||
|
{
|
||||||
|
oneof_reader<T> ret;
|
||||||
|
ret.add(a1);
|
||||||
|
ret.add(a2);
|
||||||
|
ret.add(a3);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
oneof_reader<T> oneof(T a1, T a2, T a3, T a4)
|
||||||
|
{
|
||||||
|
oneof_reader<T> ret;
|
||||||
|
ret.add(a1);
|
||||||
|
ret.add(a2);
|
||||||
|
ret.add(a3);
|
||||||
|
ret.add(a4);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
oneof_reader<T> oneof(T a1, T a2, T a3, T a4, T a5)
|
||||||
|
{
|
||||||
|
oneof_reader<T> ret;
|
||||||
|
ret.add(a1);
|
||||||
|
ret.add(a2);
|
||||||
|
ret.add(a3);
|
||||||
|
ret.add(a4);
|
||||||
|
ret.add(a5);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
oneof_reader<T> oneof(T a1, T a2, T a3, T a4, T a5, T a6)
|
||||||
|
{
|
||||||
|
oneof_reader<T> ret;
|
||||||
|
ret.add(a1);
|
||||||
|
ret.add(a2);
|
||||||
|
ret.add(a3);
|
||||||
|
ret.add(a4);
|
||||||
|
ret.add(a5);
|
||||||
|
ret.add(a6);
|
||||||
|
return ret;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
oneof_reader<T> oneof(T a1, T a2, T a3, T a4, T a5, T a6, T a7)
|
||||||
|
{
|
||||||
|
oneof_reader<T> 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 <class T>
|
||||||
|
oneof_reader<T> oneof(T a1, T a2, T a3, T a4, T a5, T a6, T a7, T a8)
|
||||||
|
{
|
||||||
|
oneof_reader<T> 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 <class T>
|
||||||
|
oneof_reader<T> oneof(T a1, T a2, T a3, T a4, T a5, T a6, T a7, T a8, T a9)
|
||||||
|
{
|
||||||
|
oneof_reader<T> 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 <class T>
|
||||||
|
oneof_reader<T> oneof(T a1, T a2, T a3, T a4, T a5, T a6, T a7, T a8, T a9, T a10)
|
||||||
|
{
|
||||||
|
oneof_reader<T> 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<std::string, option_base*>::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 <class T>
|
||||||
|
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<T>());
|
||||||
|
}
|
||||||
|
|
||||||
|
template <class T, class F>
|
||||||
|
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<T, F>(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 <class T>
|
||||||
|
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<T> *p=dynamic_cast<const option_with_value<T>*>(options.find(name)->second);
|
||||||
|
if (p==NULL) throw cmdline_error("type mismatch flag '"+name+"'");
|
||||||
|
return p->get();
|
||||||
|
}
|
||||||
|
|
||||||
|
const std::vector<std::string> &rest() const {
|
||||||
|
return others;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool parse(const std::string &arg){
|
||||||
|
std::vector<std::string> args;
|
||||||
|
|
||||||
|
std::string buf;
|
||||||
|
bool in_quote=false;
|
||||||
|
for (std::string::size_type i=0; i<arg.length(); i++){
|
||||||
|
if (arg[i]=='\"'){
|
||||||
|
in_quote=!in_quote;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (arg[i]==' ' && !in_quote){
|
||||||
|
args.push_back(buf);
|
||||||
|
buf="";
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (arg[i]=='\\'){
|
||||||
|
i++;
|
||||||
|
if (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.size(); i++)
|
||||||
|
std::cout<<"\""<<args[i]<<"\""<<std::endl;
|
||||||
|
|
||||||
|
return parse(args);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool parse(const std::vector<std::string> &args){
|
||||||
|
int argc=static_cast<int>(args.size());
|
||||||
|
std::vector<const char*> argv(argc);
|
||||||
|
|
||||||
|
for (int i=0; i<argc; i++)
|
||||||
|
argv[i]=args[i].c_str();
|
||||||
|
|
||||||
|
return parse(argc, &argv[0]);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool parse(int argc, const char * const argv[]){
|
||||||
|
errors.clear();
|
||||||
|
others.clear();
|
||||||
|
|
||||||
|
if (argc<1){
|
||||||
|
errors.push_back("argument number must be longer than 0");
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
if (prog_name=="")
|
||||||
|
prog_name=argv[0];
|
||||||
|
|
||||||
|
std::map<char, std::string> lookup;
|
||||||
|
for (std::map<std::string, option_base*>::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<argc; i++){
|
||||||
|
if (strncmp(argv[i], "--", 2)==0){
|
||||||
|
const char *p=strchr(argv[i]+2, '=');
|
||||||
|
if (p){
|
||||||
|
std::string name(argv[i]+2, p);
|
||||||
|
std::string val(p+1);
|
||||||
|
set_option(name, val);
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
std::string name(argv[i]+2);
|
||||||
|
if (options.count(name)==0){
|
||||||
|
errors.push_back("undefined option: --"+name);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if (options[name]->has_value()){
|
||||||
|
if (i+1>=argc){
|
||||||
|
errors.push_back("option needs value: --"+name);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
i++;
|
||||||
|
set_option(name, argv[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
set_option(name);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else if (strncmp(argv[i], "-", 1)==0){
|
||||||
|
if (!argv[i][1]) continue;
|
||||||
|
char last=argv[i][1];
|
||||||
|
for (int j=2; argv[i][j]; j++){
|
||||||
|
last=argv[i][j];
|
||||||
|
if (lookup.count(argv[i][j-1])==0){
|
||||||
|
errors.push_back(std::string("undefined short option: -")+argv[i][j-1]);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if (lookup[argv[i][j-1]]==""){
|
||||||
|
errors.push_back(std::string("ambiguous short option: -")+argv[i][j-1]);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
set_option(lookup[argv[i][j-1]]);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (lookup.count(last)==0){
|
||||||
|
errors.push_back(std::string("undefined short option: -")+last);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
if (lookup[last]==""){
|
||||||
|
errors.push_back(std::string("ambiguous short option: -")+last);
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (i+1<argc && options[lookup[last]]->has_value()){
|
||||||
|
set_option(lookup[last], argv[i+1]);
|
||||||
|
i++;
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
set_option(lookup[last]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
others.push_back(argv[i]);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
for (std::map<std::string, option_base*>::iterator p=options.begin();
|
||||||
|
p!=options.end(); p++)
|
||||||
|
if (!p->second->valid())
|
||||||
|
errors.push_back("need option: --"+std::string(p->first));
|
||||||
|
|
||||||
|
return errors.size()==0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void parse_check(const std::string &arg){
|
||||||
|
if (!options.count("help"))
|
||||||
|
add("help", '?', "print this message");
|
||||||
|
check(0, parse(arg));
|
||||||
|
}
|
||||||
|
|
||||||
|
void parse_check(const std::vector<std::string> &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; i<errors.size(); i++)
|
||||||
|
oss<<errors[i]<<std::endl;
|
||||||
|
return oss.str();
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string usage() const {
|
||||||
|
std::ostringstream oss;
|
||||||
|
oss<<"usage: "<<prog_name<<" ";
|
||||||
|
for (size_t i=0; i<ordered.size(); i++){
|
||||||
|
if (ordered[i]->must())
|
||||||
|
oss<<ordered[i]->short_description()<<" ";
|
||||||
|
}
|
||||||
|
|
||||||
|
oss<<"[options] ... "<<ftr<<std::endl;
|
||||||
|
oss<<"options:"<<std::endl;
|
||||||
|
|
||||||
|
size_t max_width=0;
|
||||||
|
for (size_t i=0; i<ordered.size(); i++){
|
||||||
|
max_width=std::max(max_width, ordered[i]->name().length());
|
||||||
|
}
|
||||||
|
for (size_t i=0; i<ordered.size(); i++){
|
||||||
|
if (ordered[i]->short_name()){
|
||||||
|
oss<<" -"<<ordered[i]->short_name()<<", ";
|
||||||
|
}
|
||||||
|
else{
|
||||||
|
oss<<" ";
|
||||||
|
}
|
||||||
|
|
||||||
|
oss<<"--"<<ordered[i]->name();
|
||||||
|
for (size_t j=ordered[i]->name().length(); j<max_width+4; j++)
|
||||||
|
oss<<' ';
|
||||||
|
oss<<ordered[i]->description()<<std::endl;
|
||||||
|
}
|
||||||
|
return oss.str();
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
|
||||||
|
void check(int argc, bool ok){
|
||||||
|
if ((argc==1 && !ok) || exist("help")){
|
||||||
|
std::cerr<<usage();
|
||||||
|
exit(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!ok){
|
||||||
|
std::cerr<<error()<<std::endl<<usage();
|
||||||
|
exit(1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_option(const std::string &name){
|
||||||
|
if (options.count(name)==0){
|
||||||
|
errors.push_back("undefined option: --"+name);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
if (!options[name]->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 T>
|
||||||
|
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<T>();
|
||||||
|
}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
std::string full_description(const std::string &desc){
|
||||||
|
return
|
||||||
|
desc+" ("+detail::readable_typename<T>()+
|
||||||
|
(need?"":" [="+detail::default_value<T>(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 T, class F>
|
||||||
|
class option_with_value_with_reader : public option_with_value<T> {
|
||||||
|
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<T>(name, short_name, need, def, desc), reader(reader){
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
T read(const std::string &s){
|
||||||
|
return reader(s);
|
||||||
|
}
|
||||||
|
|
||||||
|
F reader;
|
||||||
|
};
|
||||||
|
|
||||||
|
std::map<std::string, option_base*> options;
|
||||||
|
std::vector<option_base*> ordered;
|
||||||
|
std::string ftr;
|
||||||
|
|
||||||
|
std::string prog_name;
|
||||||
|
std::vector<std::string> others;
|
||||||
|
|
||||||
|
std::vector<std::string> errors;
|
||||||
|
};
|
||||||
|
|
||||||
|
} // cmdline
|
87
lidar_driver/include/Livox/third_party/spdlog/spdlog/async.h
vendored
Normal file
87
lidar_driver/include/Livox/third_party/spdlog/spdlog/async.h
vendored
Normal file
@ -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 <memory>
|
||||||
|
#include <mutex>
|
||||||
|
|
||||||
|
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<async_overflow_policy OverflowPolicy = async_overflow_policy::block>
|
||||||
|
struct async_factory_impl
|
||||||
|
{
|
||||||
|
template<typename Sink, typename... SinkArgs>
|
||||||
|
static std::shared_ptr<async_logger> create(std::string logger_name, SinkArgs &&... args)
|
||||||
|
{
|
||||||
|
auto ®istry_inst = details::registry::instance();
|
||||||
|
|
||||||
|
// create global thread pool if not already exists..
|
||||||
|
std::lock_guard<std::recursive_mutex> tp_lock(registry_inst.tp_mutex());
|
||||||
|
auto tp = registry_inst.get_tp();
|
||||||
|
if (tp == nullptr)
|
||||||
|
{
|
||||||
|
tp = std::make_shared<details::thread_pool>(details::default_async_q_size, 1);
|
||||||
|
registry_inst.set_tp(tp);
|
||||||
|
}
|
||||||
|
|
||||||
|
auto sink = std::make_shared<Sink>(std::forward<SinkArgs>(args)...);
|
||||||
|
auto new_logger = std::make_shared<async_logger>(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<async_overflow_policy::block>;
|
||||||
|
using async_factory_nonblock = async_factory_impl<async_overflow_policy::overrun_oldest>;
|
||||||
|
|
||||||
|
template<typename Sink, typename... SinkArgs>
|
||||||
|
inline std::shared_ptr<spdlog::logger> create_async(std::string logger_name, SinkArgs &&... sink_args)
|
||||||
|
{
|
||||||
|
return async_factory::create<Sink>(std::move(logger_name), std::forward<SinkArgs>(sink_args)...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Sink, typename... SinkArgs>
|
||||||
|
inline std::shared_ptr<spdlog::logger> create_async_nb(std::string logger_name, SinkArgs &&... sink_args)
|
||||||
|
{
|
||||||
|
return async_factory_nonblock::create<Sink>(std::move(logger_name), std::forward<SinkArgs>(sink_args)...);
|
||||||
|
}
|
||||||
|
|
||||||
|
// set global thread pool.
|
||||||
|
inline void init_thread_pool(size_t q_size, size_t thread_count)
|
||||||
|
{
|
||||||
|
auto tp = std::make_shared<details::thread_pool>(q_size, thread_count);
|
||||||
|
details::registry::instance().set_tp(std::move(tp));
|
||||||
|
}
|
||||||
|
|
||||||
|
// get the global thread pool.
|
||||||
|
inline std::shared_ptr<spdlog::details::thread_pool> thread_pool()
|
||||||
|
{
|
||||||
|
return details::registry::instance().get_tp();
|
||||||
|
}
|
||||||
|
} // namespace spdlog
|
73
lidar_driver/include/Livox/third_party/spdlog/spdlog/async_logger.h
vendored
Normal file
73
lidar_driver/include/Livox/third_party/spdlog/spdlog/async_logger.h
vendored
Normal file
@ -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 <chrono>
|
||||||
|
#include <memory>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
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<async_logger>, public logger
|
||||||
|
{
|
||||||
|
friend class details::thread_pool;
|
||||||
|
|
||||||
|
public:
|
||||||
|
template<typename It>
|
||||||
|
async_logger(std::string logger_name, It begin, It end, std::weak_ptr<details::thread_pool> tp,
|
||||||
|
async_overflow_policy overflow_policy = async_overflow_policy::block);
|
||||||
|
|
||||||
|
async_logger(std::string logger_name, sinks_init_list sinks_list, std::weak_ptr<details::thread_pool> tp,
|
||||||
|
async_overflow_policy overflow_policy = async_overflow_policy::block);
|
||||||
|
|
||||||
|
async_logger(std::string logger_name, sink_ptr single_sink, std::weak_ptr<details::thread_pool> tp,
|
||||||
|
async_overflow_policy overflow_policy = async_overflow_policy::block);
|
||||||
|
|
||||||
|
std::shared_ptr<logger> 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<details::thread_pool> thread_pool_;
|
||||||
|
async_overflow_policy overflow_policy_;
|
||||||
|
};
|
||||||
|
} // namespace spdlog
|
||||||
|
|
||||||
|
#include "details/async_logger_impl.h"
|
246
lidar_driver/include/Livox/third_party/spdlog/spdlog/common.h
vendored
Normal file
246
lidar_driver/include/Livox/third_party/spdlog/spdlog/common.h
vendored
Normal file
@ -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 <atomic>
|
||||||
|
#include <chrono>
|
||||||
|
#include <functional>
|
||||||
|
#include <initializer_list>
|
||||||
|
#include <memory>
|
||||||
|
#include <stdexcept>
|
||||||
|
#include <string>
|
||||||
|
#include <cstring>
|
||||||
|
#include <type_traits>
|
||||||
|
#include <unordered_map>
|
||||||
|
|
||||||
|
#if defined(SPDLOG_WCHAR_FILENAMES) || defined(SPDLOG_WCHAR_TO_UTF8_SUPPORT)
|
||||||
|
#include <codecvt>
|
||||||
|
#include <locale>
|
||||||
|
#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<sinks::sink>;
|
||||||
|
using sinks_init_list = std::initializer_list<sink_ptr>;
|
||||||
|
using log_err_handler = std::function<void(const std::string &err_msg)>;
|
||||||
|
|
||||||
|
// 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<int>;
|
||||||
|
#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_enum>(level);
|
||||||
|
}
|
||||||
|
level++;
|
||||||
|
}
|
||||||
|
return level::off;
|
||||||
|
}
|
||||||
|
|
||||||
|
using level_hasher = std::hash<int>;
|
||||||
|
} // 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<uint32_t>(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<typename T, typename... Args>
|
||||||
|
std::unique_ptr<T> make_unique(Args &&... args)
|
||||||
|
{
|
||||||
|
static_assert(!std::is_array<T>::value, "arrays not supported");
|
||||||
|
return std::unique_ptr<T>(new T(std::forward<Args>(args)...));
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
} // namespace details
|
||||||
|
} // namespace spdlog
|
110
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/async_logger_impl.h
vendored
Normal file
110
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/async_logger_impl.h
vendored
Normal file
@ -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 <chrono>
|
||||||
|
#include <memory>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
template<typename It>
|
||||||
|
inline spdlog::async_logger::async_logger(
|
||||||
|
std::string logger_name, It begin, It end, std::weak_ptr<details::thread_pool> 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<details::thread_pool> 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<details::thread_pool> 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::logger> spdlog::async_logger::clone(std::string new_name)
|
||||||
|
{
|
||||||
|
auto cloned = std::make_shared<spdlog::async_logger>(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);
|
||||||
|
}
|
72
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/circular_q.h
vendored
Normal file
72
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/circular_q.h
vendored
Normal file
@ -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 <vector>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace details {
|
||||||
|
template<typename T>
|
||||||
|
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<T>::size_type head_ = 0;
|
||||||
|
typename std::vector<T>::size_type tail_ = 0;
|
||||||
|
|
||||||
|
std::vector<T> v_;
|
||||||
|
|
||||||
|
size_t overrun_counter_ = 0;
|
||||||
|
};
|
||||||
|
} // namespace details
|
||||||
|
} // namespace spdlog
|
74
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/console_globals.h
vendored
Normal file
74
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/console_globals.h
vendored
Normal file
@ -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 <cstdio>
|
||||||
|
#include <mutex>
|
||||||
|
|
||||||
|
#ifdef _WIN32
|
||||||
|
|
||||||
|
#ifndef NOMINMAX
|
||||||
|
#define NOMINMAX // prevent windows redefining min/max
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef WIN32_LEAN_AND_MEAN
|
||||||
|
#define WIN32_LEAN_AND_MEAN
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <windows.h>
|
||||||
|
#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
|
152
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/file_helper.h
vendored
Normal file
152
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/file_helper.h
vendored
Normal file
@ -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 <cerrno>
|
||||||
|
#include <chrono>
|
||||||
|
#include <cstdio>
|
||||||
|
#include <string>
|
||||||
|
#include <thread>
|
||||||
|
#include <tuple>
|
||||||
|
|
||||||
|
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<filename_t, filename_t> 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
|
122
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/fmt_helper.h
vendored
Normal file
122
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/fmt_helper.h
vendored
Normal file
@ -0,0 +1,122 @@
|
|||||||
|
//
|
||||||
|
// Created by gabi on 6/15/18.
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <chrono>
|
||||||
|
#include <type_traits>
|
||||||
|
#include "spdlog/fmt/fmt.h"
|
||||||
|
|
||||||
|
// Some fmt helpers to efficiently format and pad ints and strings
|
||||||
|
namespace spdlog {
|
||||||
|
namespace details {
|
||||||
|
namespace fmt_helper {
|
||||||
|
|
||||||
|
template<size_t Buffer_Size>
|
||||||
|
inline spdlog::string_view_t to_string_view(const fmt::basic_memory_buffer<char, Buffer_Size> &buf) SPDLOG_NOEXCEPT
|
||||||
|
{
|
||||||
|
return spdlog::string_view_t(buf.data(), buf.size());
|
||||||
|
}
|
||||||
|
|
||||||
|
template<size_t Buffer_Size1, size_t Buffer_Size2>
|
||||||
|
inline void append_buf(const fmt::basic_memory_buffer<char, Buffer_Size1> &buf, fmt::basic_memory_buffer<char, Buffer_Size2> &dest)
|
||||||
|
{
|
||||||
|
auto *buf_ptr = buf.data();
|
||||||
|
dest.append(buf_ptr, buf_ptr + buf.size());
|
||||||
|
}
|
||||||
|
|
||||||
|
template<size_t Buffer_Size>
|
||||||
|
inline void append_string_view(spdlog::string_view_t view, fmt::basic_memory_buffer<char, Buffer_Size> &dest)
|
||||||
|
{
|
||||||
|
auto *buf_ptr = view.data();
|
||||||
|
if (buf_ptr != nullptr)
|
||||||
|
{
|
||||||
|
dest.append(buf_ptr, buf_ptr + view.size());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename T, size_t Buffer_Size>
|
||||||
|
inline void append_int(T n, fmt::basic_memory_buffer<char, Buffer_Size> &dest)
|
||||||
|
{
|
||||||
|
fmt::format_int i(n);
|
||||||
|
dest.append(i.data(), i.data() + i.size());
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
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<unsigned>(fmt::internal::count_digits(static_cast<count_type>(n)));
|
||||||
|
}
|
||||||
|
|
||||||
|
template<size_t Buffer_Size>
|
||||||
|
inline void pad2(int n, fmt::basic_memory_buffer<char, Buffer_Size> &dest)
|
||||||
|
{
|
||||||
|
if (n > 99)
|
||||||
|
{
|
||||||
|
append_int(n, dest);
|
||||||
|
}
|
||||||
|
else if (n > 9) // 10-99
|
||||||
|
{
|
||||||
|
dest.push_back(static_cast<char>('0' + n / 10));
|
||||||
|
dest.push_back(static_cast<char>('0' + n % 10));
|
||||||
|
}
|
||||||
|
else if (n >= 0) // 0-9
|
||||||
|
{
|
||||||
|
dest.push_back('0');
|
||||||
|
dest.push_back(static_cast<char>('0' + n));
|
||||||
|
}
|
||||||
|
else // negatives (unlikely, but just in case, let fmt deal with it)
|
||||||
|
{
|
||||||
|
fmt::format_to(dest, "{:02}", n);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename T, size_t Buffer_Size>
|
||||||
|
inline void pad_uint(T n, unsigned int width, fmt::basic_memory_buffer<char, Buffer_Size> &dest)
|
||||||
|
{
|
||||||
|
static_assert(std::is_unsigned<T>::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<typename T, size_t Buffer_Size>
|
||||||
|
inline void pad3(T n, fmt::basic_memory_buffer<char, Buffer_Size> &dest)
|
||||||
|
{
|
||||||
|
pad_uint(n, 3, dest);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename T, size_t Buffer_Size>
|
||||||
|
inline void pad6(T n, fmt::basic_memory_buffer<char, Buffer_Size> &dest)
|
||||||
|
{
|
||||||
|
pad_uint(n, 6, dest);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename T, size_t Buffer_Size>
|
||||||
|
inline void pad9(T n, fmt::basic_memory_buffer<char, Buffer_Size> &dest)
|
||||||
|
{
|
||||||
|
pad_uint(n, 9, dest);
|
||||||
|
}
|
||||||
|
|
||||||
|
// return fraction of a second of the given time_point.
|
||||||
|
// e.g.
|
||||||
|
// fraction<std::milliseconds>(tp) -> will return the millis part of the second
|
||||||
|
template<typename ToDuration>
|
||||||
|
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<seconds>(duration);
|
||||||
|
return duration_cast<ToDuration>(duration) - duration_cast<ToDuration>(secs);
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace fmt_helper
|
||||||
|
} // namespace details
|
||||||
|
} // namespace spdlog
|
55
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/log_msg.h
vendored
Normal file
55
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/log_msg.h
vendored
Normal file
@ -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 <string>
|
||||||
|
#include <utility>
|
||||||
|
|
||||||
|
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
|
435
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/logger_impl.h
vendored
Normal file
435
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/logger_impl.h
vendored
Normal file
@ -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 <memory>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
#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<typename It>
|
||||||
|
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<spdlog::formatter> 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<spdlog::pattern_formatter>(std::move(pattern), time_type);
|
||||||
|
set_formatter(std::move(new_formatter));
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
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<typename... Args>
|
||||||
|
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<class T>
|
||||||
|
inline void spdlog::logger::log(level::level_enum lvl, const T &msg)
|
||||||
|
{
|
||||||
|
log(source_loc{}, lvl, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<class T, typename std::enable_if<std::is_convertible<T, spdlog::string_view_t>::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<class T, typename std::enable_if<!std::is_convertible<T, spdlog::string_view_t>::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<typename... Args>
|
||||||
|
inline void spdlog::logger::trace(const char *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(level::trace, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
inline void spdlog::logger::debug(const char *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(level::debug, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
inline void spdlog::logger::info(const char *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(level::info, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
inline void spdlog::logger::warn(const char *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(level::warn, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
inline void spdlog::logger::error(const char *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(level::err, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
inline void spdlog::logger::critical(const char *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(level::critical, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
inline void spdlog::logger::trace(const T &msg)
|
||||||
|
{
|
||||||
|
log(level::trace, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
inline void spdlog::logger::debug(const T &msg)
|
||||||
|
{
|
||||||
|
log(level::debug, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
inline void spdlog::logger::info(const T &msg)
|
||||||
|
{
|
||||||
|
log(level::info, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
inline void spdlog::logger::warn(const T &msg)
|
||||||
|
{
|
||||||
|
log(level::warn, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
inline void spdlog::logger::error(const T &msg)
|
||||||
|
{
|
||||||
|
log(level::err, msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
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<int>(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<typename... Args>
|
||||||
|
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<typename... Args>
|
||||||
|
inline void spdlog::logger::log(level::level_enum lvl, const wchar_t *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(source_loc{}, lvl, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
inline void spdlog::logger::trace(const wchar_t *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(level::trace, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
inline void spdlog::logger::debug(const wchar_t *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(level::debug, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
inline void spdlog::logger::info(const wchar_t *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(level::info, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
inline void spdlog::logger::warn(const wchar_t *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(level::warn, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
inline void spdlog::logger::error(const wchar_t *fmt, const Args &... args)
|
||||||
|
{
|
||||||
|
log(level::err, fmt, args...);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
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<spdlog::level::level_enum>(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::level::level_enum>(SPDLOG_ACTIVE_LEVEL);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline spdlog::level::level_enum spdlog::logger::level() const
|
||||||
|
{
|
||||||
|
return static_cast<spdlog::level::level_enum>(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::sink_ptr> &spdlog::logger::sinks() const
|
||||||
|
{
|
||||||
|
return sinks_;
|
||||||
|
}
|
||||||
|
|
||||||
|
inline std::vector<spdlog::sink_ptr> &spdlog::logger::sinks()
|
||||||
|
{
|
||||||
|
return sinks_;
|
||||||
|
}
|
||||||
|
|
||||||
|
inline std::shared_ptr<spdlog::logger> spdlog::logger::clone(std::string logger_name)
|
||||||
|
{
|
||||||
|
auto cloned = std::make_shared<spdlog::logger>(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;
|
||||||
|
}
|
121
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/mpmc_blocking_q.h
vendored
Normal file
121
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/mpmc_blocking_q.h
vendored
Normal file
@ -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 <condition_variable>
|
||||||
|
#include <mutex>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace details {
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
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<std::mutex> 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<std::mutex> 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<std::mutex> 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<std::mutex> 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<std::mutex> 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<std::mutex> 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<std::mutex> 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<T> q_;
|
||||||
|
};
|
||||||
|
} // namespace details
|
||||||
|
} // namespace spdlog
|
45
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/null_mutex.h
vendored
Normal file
45
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/null_mutex.h
vendored
Normal file
@ -0,0 +1,45 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include <atomic>
|
||||||
|
// 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
|
421
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/os.h
vendored
Normal file
421
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/os.h
vendored
Normal file
@ -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 <algorithm>
|
||||||
|
#include <chrono>
|
||||||
|
#include <cstdio>
|
||||||
|
#include <cstdlib>
|
||||||
|
#include <cstring>
|
||||||
|
#include <ctime>
|
||||||
|
#include <functional>
|
||||||
|
#include <string>
|
||||||
|
#include <sys/stat.h>
|
||||||
|
#include <sys/types.h>
|
||||||
|
#include <thread>
|
||||||
|
|
||||||
|
#ifdef _WIN32
|
||||||
|
|
||||||
|
#ifndef NOMINMAX
|
||||||
|
#define NOMINMAX // prevent windows redefining min/max
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifndef WIN32_LEAN_AND_MEAN
|
||||||
|
#define WIN32_LEAN_AND_MEAN
|
||||||
|
#endif
|
||||||
|
#include <io.h> // _get_osfhandle and _isatty support
|
||||||
|
#include <process.h> // _get_pid support
|
||||||
|
#include <windows.h>
|
||||||
|
|
||||||
|
#ifdef __MINGW32__
|
||||||
|
#include <share.h>
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#else // unix
|
||||||
|
|
||||||
|
#include <fcntl.h>
|
||||||
|
#include <unistd.h>
|
||||||
|
|
||||||
|
#ifdef __linux__
|
||||||
|
#include <sys/syscall.h> //Use gettid() syscall under linux to get thread id
|
||||||
|
|
||||||
|
#elif __FreeBSD__
|
||||||
|
#include <sys/thr.h> //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<log_clock, typename log_clock::duration>(
|
||||||
|
std::chrono::duration_cast<typename log_clock::duration>(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<size_t>(ret);
|
||||||
|
}
|
||||||
|
|
||||||
|
#else // windows 32 bits
|
||||||
|
long ret = _filelength(fd);
|
||||||
|
if (ret >= 0)
|
||||||
|
{
|
||||||
|
return static_cast<size_t>(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<size_t>(st.st_size);
|
||||||
|
}
|
||||||
|
#else // unix 32 bits or cygwin
|
||||||
|
struct stat st;
|
||||||
|
|
||||||
|
if (fstat(fd, &st) == 0)
|
||||||
|
{
|
||||||
|
return static_cast<size_t>(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<int>(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<size_t>(::GetCurrentThreadId());
|
||||||
|
#elif __linux__
|
||||||
|
#if defined(__ANDROID__) && defined(__ANDROID_API__) && (__ANDROID_API__ < 21)
|
||||||
|
#define SYS_gettid __NR_gettid
|
||||||
|
#endif
|
||||||
|
return static_cast<size_t>(syscall(SYS_gettid));
|
||||||
|
#elif __FreeBSD__
|
||||||
|
long tid;
|
||||||
|
thr_self(&tid);
|
||||||
|
return static_cast<size_t>(tid);
|
||||||
|
#elif __APPLE__
|
||||||
|
uint64_t tid;
|
||||||
|
pthread_threadid_np(nullptr, &tid);
|
||||||
|
return static_cast<size_t>(tid);
|
||||||
|
#else // Default to standard C++11 (other Unix)
|
||||||
|
return static_cast<size_t>(std::hash<std::thread::id>()(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<std::codecvt_utf8<wchar_t>, 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<int>(::GetCurrentProcessId());
|
||||||
|
#else
|
||||||
|
return static_cast<int>(::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
|
1336
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/pattern_formatter.h
vendored
Normal file
1336
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/pattern_formatter.h
vendored
Normal file
File diff suppressed because it is too large
Load Diff
71
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/periodic_worker.h
vendored
Normal file
71
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/periodic_worker.h
vendored
Normal file
@ -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 <chrono>
|
||||||
|
#include <condition_variable>
|
||||||
|
#include <functional>
|
||||||
|
#include <mutex>
|
||||||
|
#include <thread>
|
||||||
|
namespace spdlog {
|
||||||
|
namespace details {
|
||||||
|
|
||||||
|
class periodic_worker
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
periodic_worker(const std::function<void()> &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<std::mutex> 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<std::mutex> 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
|
285
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/registry.h
vendored
Normal file
285
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/registry.h
vendored
Normal file
@ -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 <chrono>
|
||||||
|
#include <functional>
|
||||||
|
#include <memory>
|
||||||
|
#include <string>
|
||||||
|
#include <unordered_map>
|
||||||
|
|
||||||
|
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<logger> new_logger)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(logger_map_mutex_);
|
||||||
|
register_logger_(std::move(new_logger));
|
||||||
|
}
|
||||||
|
|
||||||
|
void initialize_logger(std::shared_ptr<logger> new_logger)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> 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<logger> get(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(logger_map_mutex_);
|
||||||
|
auto found = loggers_.find(logger_name);
|
||||||
|
return found == loggers_.end() ? nullptr : found->second;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::shared_ptr<logger> default_logger()
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> 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<logger> new_default_logger)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> 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<thread_pool> tp)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::recursive_mutex> lock(tp_mutex_);
|
||||||
|
tp_ = std::move(tp);
|
||||||
|
}
|
||||||
|
|
||||||
|
std::shared_ptr<thread_pool> get_tp()
|
||||||
|
{
|
||||||
|
std::lock_guard<std::recursive_mutex> 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> formatter)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> 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<std::mutex> 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<std::mutex> 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<std::mutex> lock(flusher_mutex_);
|
||||||
|
std::function<void()> clbk = std::bind(®istry::flush_all, this);
|
||||||
|
periodic_flusher_ = details::make_unique<periodic_worker>(clbk, interval);
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_error_handler(log_err_handler handler)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(logger_map_mutex_);
|
||||||
|
for (auto &l : loggers_)
|
||||||
|
{
|
||||||
|
l.second->set_error_handler(handler);
|
||||||
|
}
|
||||||
|
err_handler_ = handler;
|
||||||
|
}
|
||||||
|
|
||||||
|
void apply_all(const std::function<void(const std::shared_ptr<logger>)> &fun)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(logger_map_mutex_);
|
||||||
|
for (auto &l : loggers_)
|
||||||
|
{
|
||||||
|
fun(l.second);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void flush_all()
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(logger_map_mutex_);
|
||||||
|
for (auto &l : loggers_)
|
||||||
|
{
|
||||||
|
l.second->flush();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void drop(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> 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<std::mutex> lock(logger_map_mutex_);
|
||||||
|
loggers_.clear();
|
||||||
|
default_logger_.reset();
|
||||||
|
}
|
||||||
|
|
||||||
|
// clean all resources and threads started by the registry
|
||||||
|
void shutdown()
|
||||||
|
{
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> lock(flusher_mutex_);
|
||||||
|
periodic_flusher_.reset();
|
||||||
|
}
|
||||||
|
|
||||||
|
drop_all();
|
||||||
|
|
||||||
|
{
|
||||||
|
std::lock_guard<std::recursive_mutex> lock(tp_mutex_);
|
||||||
|
tp_.reset();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
std::recursive_mutex &tp_mutex()
|
||||||
|
{
|
||||||
|
return tp_mutex_;
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_automatic_registration(bool automatic_regsistration)
|
||||||
|
{
|
||||||
|
std::lock_guard<std::mutex> 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<sinks::wincolor_stdout_sink_mt>();
|
||||||
|
#else
|
||||||
|
auto color_sink = std::make_shared<sinks::ansicolor_stdout_sink_mt>();
|
||||||
|
#endif
|
||||||
|
|
||||||
|
const char *default_logger_name = "";
|
||||||
|
default_logger_ = std::make_shared<spdlog::logger>(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<logger> 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<std::string, std::shared_ptr<logger>> loggers_;
|
||||||
|
std::unique_ptr<formatter> formatter_;
|
||||||
|
level::level_enum level_ = spdlog::logger::default_level();
|
||||||
|
level::level_enum flush_level_ = level::off;
|
||||||
|
log_err_handler err_handler_;
|
||||||
|
std::shared_ptr<thread_pool> tp_;
|
||||||
|
std::unique_ptr<periodic_worker> periodic_flusher_;
|
||||||
|
std::shared_ptr<logger> default_logger_;
|
||||||
|
bool automatic_registration_ = true;
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace details
|
||||||
|
} // namespace spdlog
|
238
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/thread_pool.h
vendored
Normal file
238
lidar_driver/include/Livox/third_party/spdlog/spdlog/details/thread_pool.h
vendored
Normal file
@ -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 <chrono>
|
||||||
|
#include <memory>
|
||||||
|
#include <thread>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace details {
|
||||||
|
|
||||||
|
using async_logger_ptr = std::shared_ptr<spdlog::async_logger>;
|
||||||
|
|
||||||
|
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<char, 176> 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<item_type>;
|
||||||
|
|
||||||
|
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<std::thread> 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
|
172
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bin_to_hex.h
vendored
Normal file
172
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bin_to_hex.h
vendored
Normal file
@ -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<char> 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<typename It>
|
||||||
|
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<typename Container>
|
||||||
|
inline details::bytes_range<typename Container::const_iterator> 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<Iter>(std::begin(container), std::end(container));
|
||||||
|
}
|
||||||
|
|
||||||
|
// create bytes_range from ranges
|
||||||
|
template<typename It>
|
||||||
|
inline details::bytes_range<It> to_hex(const It range_begin, const It range_end)
|
||||||
|
{
|
||||||
|
return details::bytes_range<It>(range_begin, range_end);
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace spdlog
|
||||||
|
|
||||||
|
namespace fmt {
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
struct formatter<spdlog::details::bytes_range<T>>
|
||||||
|
{
|
||||||
|
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<typename ParseContext>
|
||||||
|
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<typename FormatContext, typename Container>
|
||||||
|
auto format(const spdlog::details::bytes_range<Container> &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<unsigned char>(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<typename It>
|
||||||
|
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
|
23
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/LICENSE.rst
vendored
Normal file
23
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/LICENSE.rst
vendored
Normal file
@ -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.
|
452
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/chrono.h
vendored
Normal file
452
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/chrono.h
vendored
Normal file
@ -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 <chrono>
|
||||||
|
#include <ctime>
|
||||||
|
#include <locale>
|
||||||
|
#include <sstream>
|
||||||
|
|
||||||
|
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 <typename Char, typename Handler>
|
||||||
|
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 <typename Char>
|
||||||
|
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 <typename Int>
|
||||||
|
inline int to_int(Int value) {
|
||||||
|
FMT_ASSERT(value >= (std::numeric_limits<int>::min)() &&
|
||||||
|
value <= (std::numeric_limits<int>::max)(), "invalid value");
|
||||||
|
return static_cast<int>(value);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename FormatContext, typename OutputIt>
|
||||||
|
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<int>::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<char_type>(out, n, num_digits);
|
||||||
|
}
|
||||||
|
|
||||||
|
void format_localized(const tm &time, const char *format) {
|
||||||
|
auto locale = context.locale().template get<std::locale>();
|
||||||
|
auto &facet = std::use_facet<std::time_put<char_type>>(locale);
|
||||||
|
std::basic_ostringstream<char_type> 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 <typename Period> FMT_CONSTEXPR const char *get_units() {
|
||||||
|
return FMT_NULL;
|
||||||
|
}
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::atto>() { return "as"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::femto>() { return "fs"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::pico>() { return "ps"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::nano>() { return "ns"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::micro>() { return "µs"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::milli>() { return "ms"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::centi>() { return "cs"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::deci>() { return "ds"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::ratio<1>>() { return "s"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::deca>() { return "das"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::hecto>() { return "hs"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::kilo>() { return "ks"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::mega>() { return "Ms"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::giga>() { return "Gs"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::tera>() { return "Ts"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::peta>() { return "Ps"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::exa>() { return "Es"; }
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::ratio<60>>() {
|
||||||
|
return "m";
|
||||||
|
}
|
||||||
|
template <> FMT_CONSTEXPR const char *get_units<std::ratio<3600>>() {
|
||||||
|
return "h";
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename Rep, typename Period, typename Char>
|
||||||
|
struct formatter<std::chrono::duration<Rep, Period>, Char> {
|
||||||
|
private:
|
||||||
|
align_spec spec;
|
||||||
|
internal::arg_ref<Char> width_ref;
|
||||||
|
mutable basic_string_view<Char> format_str;
|
||||||
|
typedef std::chrono::duration<Rep, Period> duration;
|
||||||
|
|
||||||
|
struct spec_handler {
|
||||||
|
formatter &f;
|
||||||
|
basic_parse_context<Char> &context;
|
||||||
|
|
||||||
|
typedef internal::arg_ref<Char> arg_ref_type;
|
||||||
|
|
||||||
|
template <typename Id>
|
||||||
|
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 <typename Id>
|
||||||
|
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<Char> &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<Char>(&*begin, internal::to_unsigned(end - begin));
|
||||||
|
return end;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename FormatContext>
|
||||||
|
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<decltype(ctx.out()), Char> range;
|
||||||
|
basic_writer<range> w(range(ctx.out()));
|
||||||
|
if (begin == end || *begin == '}') {
|
||||||
|
if (const char *unit = get_units<Period>())
|
||||||
|
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<internal::width_checker>(
|
||||||
|
spec.width_, width_ref, ctx);
|
||||||
|
} else {
|
||||||
|
auto out = std::back_inserter(buf);
|
||||||
|
internal::chrono_formatter<FormatContext, decltype(out)> f(ctx, out);
|
||||||
|
f.s = std::chrono::duration_cast<std::chrono::seconds>(d);
|
||||||
|
f.ms = std::chrono::duration_cast<std::chrono::milliseconds>(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_
|
577
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/color.h
vendored
Normal file
577
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/color.h
vendored
Normal file
@ -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 <typename... Args>
|
||||||
|
inline void print_colored(color c, string_view format_str,
|
||||||
|
const Args & ... args) {
|
||||||
|
vprint_colored(c, format_str, make_format_args(args...));
|
||||||
|
}
|
||||||
|
template <typename... Args>
|
||||||
|
inline void print_colored(color c, wstring_view format_str,
|
||||||
|
const Args & ... args) {
|
||||||
|
vprint_colored(c, format_str, make_format_args<wformat_context>(args...));
|
||||||
|
}
|
||||||
|
|
||||||
|
inline void vprint_colored(color c, string_view format, format_args args) {
|
||||||
|
char escape[] = "\x1b[30m";
|
||||||
|
escape[3] = static_cast<char>('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<wchar_t>('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<uint32_t>(rgb_color);
|
||||||
|
}
|
||||||
|
FMT_CONSTEXPR color_type(rgb rgb_color) FMT_NOEXCEPT
|
||||||
|
: is_rgb(true), value{} {
|
||||||
|
value.rgb_color = (static_cast<uint32_t>(rgb_color.r) << 16)
|
||||||
|
| (static_cast<uint32_t>(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<uint8_t>(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<emphasis>(static_cast<uint8_t>(ems) |
|
||||||
|
static_cast<uint8_t>(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<emphasis>(static_cast<uint8_t>(ems) &
|
||||||
|
static_cast<uint8_t>(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<uint8_t>(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 <typename Char>
|
||||||
|
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<Char>('\x1b');
|
||||||
|
buffer[index++] = static_cast<Char>('[');
|
||||||
|
|
||||||
|
if (value >= 100u) {
|
||||||
|
buffer[index++] = static_cast<Char>('1');
|
||||||
|
value %= 100u;
|
||||||
|
}
|
||||||
|
buffer[index++] = static_cast<Char>('0' + value / 10u);
|
||||||
|
buffer[index++] = static_cast<Char>('0' + value % 10u);
|
||||||
|
|
||||||
|
buffer[index++] = static_cast<Char>('m');
|
||||||
|
buffer[index++] = static_cast<Char>('\0');
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
for (int i = 0; i < 7; i++) {
|
||||||
|
buffer[i] = static_cast<Char>(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<Char>(0);
|
||||||
|
}
|
||||||
|
FMT_CONSTEXPR ansi_color_escape(emphasis em) FMT_NOEXCEPT {
|
||||||
|
uint8_t em_codes[4] = {};
|
||||||
|
uint8_t em_bits = static_cast<uint8_t>(em);
|
||||||
|
if (em_bits & static_cast<uint8_t>(emphasis::bold))
|
||||||
|
em_codes[0] = 1;
|
||||||
|
if (em_bits & static_cast<uint8_t>(emphasis::italic))
|
||||||
|
em_codes[1] = 3;
|
||||||
|
if (em_bits & static_cast<uint8_t>(emphasis::underline))
|
||||||
|
em_codes[2] = 4;
|
||||||
|
if (em_bits & static_cast<uint8_t>(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<Char>('\x1b');
|
||||||
|
buffer[index++] = static_cast<Char>('[');
|
||||||
|
buffer[index++] = static_cast<Char>('0' + em_codes[i]);
|
||||||
|
buffer[index++] = static_cast<Char>('m');
|
||||||
|
}
|
||||||
|
buffer[index++] = static_cast<Char>(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<Char>('0' + c / 100);
|
||||||
|
out[1] = static_cast<Char>('0' + c / 10 % 10);
|
||||||
|
out[2] = static_cast<Char>('0' + c % 10);
|
||||||
|
out[3] = static_cast<Char>(delimiter);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
FMT_CONSTEXPR ansi_color_escape<Char>
|
||||||
|
make_foreground_color(internal::color_type foreground) FMT_NOEXCEPT {
|
||||||
|
return ansi_color_escape<Char>(foreground, internal::data::FOREGROUND_COLOR);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
FMT_CONSTEXPR ansi_color_escape<Char>
|
||||||
|
make_background_color(internal::color_type background) FMT_NOEXCEPT {
|
||||||
|
return ansi_color_escape<Char>(background, internal::data::BACKGROUND_COLOR);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
FMT_CONSTEXPR ansi_color_escape<Char>
|
||||||
|
make_emphasis(emphasis em) FMT_NOEXCEPT {
|
||||||
|
return ansi_color_escape<Char>(em);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
inline void fputs(const Char *chars, FILE *stream) FMT_NOEXCEPT {
|
||||||
|
std::fputs(chars, stream);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <>
|
||||||
|
inline void fputs<wchar_t>(const wchar_t *chars, FILE *stream) FMT_NOEXCEPT {
|
||||||
|
std::fputws(chars, stream);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
inline void reset_color(FILE *stream) FMT_NOEXCEPT {
|
||||||
|
fputs(internal::data::RESET_COLOR, stream);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <>
|
||||||
|
inline void reset_color<wchar_t>(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::FILE *> : std::false_type {};
|
||||||
|
template <>
|
||||||
|
struct is_string<const std::FILE *> : std::false_type {};
|
||||||
|
} // namespace internal
|
||||||
|
|
||||||
|
template <
|
||||||
|
typename S, typename Char = typename internal::char_t<S>::type>
|
||||||
|
void vprint(std::FILE *f, const text_style &ts, const S &format,
|
||||||
|
basic_format_args<typename buffer_context<Char>::type> args) {
|
||||||
|
bool has_style = false;
|
||||||
|
if (ts.has_emphasis()) {
|
||||||
|
has_style = true;
|
||||||
|
internal::fputs<Char>(
|
||||||
|
internal::make_emphasis<Char>(ts.get_emphasis()), f);
|
||||||
|
}
|
||||||
|
if (ts.has_foreground()) {
|
||||||
|
has_style = true;
|
||||||
|
internal::fputs<Char>(
|
||||||
|
internal::make_foreground_color<Char>(ts.get_foreground()), f);
|
||||||
|
}
|
||||||
|
if (ts.has_background()) {
|
||||||
|
has_style = true;
|
||||||
|
internal::fputs<Char>(
|
||||||
|
internal::make_background_color<Char>(ts.get_background()), f);
|
||||||
|
}
|
||||||
|
vprint(f, format, args);
|
||||||
|
if (has_style) {
|
||||||
|
internal::reset_color<Char>(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 String, typename... Args>
|
||||||
|
typename std::enable_if<internal::is_string<String>::value>::type print(
|
||||||
|
std::FILE *f, const text_style &ts, const String &format_str,
|
||||||
|
const Args &... args) {
|
||||||
|
internal::check_format_string<Args...>(format_str);
|
||||||
|
typedef typename internal::char_t<String>::type char_t;
|
||||||
|
typedef typename buffer_context<char_t>::type context_t;
|
||||||
|
format_arg_store<context_t, Args...> as{args...};
|
||||||
|
vprint(f, ts, format_str, basic_format_args<context_t>(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 String, typename... Args>
|
||||||
|
typename std::enable_if<internal::is_string<String>::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_
|
1502
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/core.h
vendored
Normal file
1502
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/core.h
vendored
Normal file
File diff suppressed because it is too large
Load Diff
972
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/format-inl.h
vendored
Normal file
972
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/format-inl.h
vendored
Normal file
@ -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 <string.h>
|
||||||
|
|
||||||
|
#include <cctype>
|
||||||
|
#include <cerrno>
|
||||||
|
#include <climits>
|
||||||
|
#include <cmath>
|
||||||
|
#include <cstdarg>
|
||||||
|
#include <cstddef> // for std::ptrdiff_t
|
||||||
|
#include <cstring> // for std::memmove
|
||||||
|
#if !defined(FMT_STATIC_THOUSANDS_SEPARATOR)
|
||||||
|
# include <locale>
|
||||||
|
#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 <windows.h>
|
||||||
|
# else
|
||||||
|
# define NOMINMAX
|
||||||
|
# include <windows.h>
|
||||||
|
# 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<int>::main_type main_type;
|
||||||
|
main_type abs_value = static_cast<main_type>(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<char8_t> 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 <typename Locale>
|
||||||
|
locale_ref::locale_ref(const Locale &loc) : locale_(&loc) {
|
||||||
|
static_assert(std::is_same<Locale, std::locale>::value, "");
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename Locale>
|
||||||
|
Locale locale_ref::get() const {
|
||||||
|
static_assert(std::is_same<Locale, std::locale>::value, "");
|
||||||
|
return locale_ ? *static_cast<const std::locale*>(locale_) : std::locale();
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
FMT_FUNC Char thousands_sep_impl(locale_ref loc) {
|
||||||
|
return std::use_facet<std::numpunct<Char> >(
|
||||||
|
loc.get<std::locale>()).thousands_sep();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#else
|
||||||
|
template <typename Char>
|
||||||
|
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 <typename T>
|
||||||
|
int char_traits<char>::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 <typename T>
|
||||||
|
int char_traits<wchar_t>::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 <typename T>
|
||||||
|
const char basic_data<T>::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 <typename T>
|
||||||
|
const uint32_t basic_data<T>::POWERS_OF_10_32[] = {
|
||||||
|
1, FMT_POWERS_OF_10(1)
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
const uint32_t basic_data<T>::ZERO_OR_POWERS_OF_10_32[] = {
|
||||||
|
0, FMT_POWERS_OF_10(1)
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
const uint64_t basic_data<T>::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 <typename T>
|
||||||
|
const uint64_t basic_data<T>::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 <typename T>
|
||||||
|
const int16_t basic_data<T>::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 <typename T> const char basic_data<T>::FOREGROUND_COLOR[] = "\x1b[38;2;";
|
||||||
|
template <typename T> const char basic_data<T>::BACKGROUND_COLOR[] = "\x1b[48;2;";
|
||||||
|
template <typename T> const char basic_data<T>::RESET_COLOR[] = "\x1b[0m";
|
||||||
|
template <typename T> const wchar_t basic_data<T>::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<unsigned char>::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<double>::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 <typename Double>
|
||||||
|
explicit fp(Double d) {
|
||||||
|
// Assume double is in the format [sign][exponent][significand].
|
||||||
|
typedef std::numeric_limits<Double> limits;
|
||||||
|
const int double_size = static_cast<int>(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<uint64_t>(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<int>(biased_e - exponent_bias - double_significand_size);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Normalizes the value converted from double and multiplied by (1 << SHIFT).
|
||||||
|
template <int SHIFT = 0>
|
||||||
|
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<int>(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<char>('0' + digit);
|
||||||
|
--exp;
|
||||||
|
uint64_t remainder = (static_cast<uint64_t>(hi) << -one.e) + lo;
|
||||||
|
if (remainder <= delta || size > max_digits) {
|
||||||
|
return grisu2_round(
|
||||||
|
buf, size, max_digits, delta, remainder,
|
||||||
|
static_cast<uint64_t>(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<char>(lo >> -one.e);
|
||||||
|
if (digit != 0 || size != 0)
|
||||||
|
buf[size++] = static_cast<char>('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 <typename F>
|
||||||
|
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 <typename Handler>
|
||||||
|
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<char>('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 <typename Handler>
|
||||||
|
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 <typename F>
|
||||||
|
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 <typename Double>
|
||||||
|
FMT_FUNC typename std::enable_if<sizeof(Double) == sizeof(uint64_t), bool>::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<uint32_t>(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 <typename Double>
|
||||||
|
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<Double, long double>::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<char>::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<int>(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<int>(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<uint32_t>(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<buffer_context<char>::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_
|
3555
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/format.h
vendored
Normal file
3555
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/format.h
vendored
Normal file
File diff suppressed because it is too large
Load Diff
77
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/locale.h
vendored
Normal file
77
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/locale.h
vendored
Normal file
@ -0,0 +1,77 @@
|
|||||||
|
// Formatting library for C++ - std::locale support
|
||||||
|
//
|
||||||
|
// Copyright (c) 2012 - present, Victor Zverovich
|
||||||
|
// All rights reserved.
|
||||||
|
//
|
||||||
|
// For the license information refer to format.h.
|
||||||
|
|
||||||
|
#ifndef FMT_LOCALE_H_
|
||||||
|
#define FMT_LOCALE_H_
|
||||||
|
|
||||||
|
#include "format.h"
|
||||||
|
#include <locale>
|
||||||
|
|
||||||
|
FMT_BEGIN_NAMESPACE
|
||||||
|
|
||||||
|
namespace internal {
|
||||||
|
template <typename Char>
|
||||||
|
typename buffer_context<Char>::type::iterator vformat_to(
|
||||||
|
const std::locale &loc, basic_buffer<Char> &buf,
|
||||||
|
basic_string_view<Char> format_str,
|
||||||
|
basic_format_args<typename buffer_context<Char>::type> args) {
|
||||||
|
typedef back_insert_range<basic_buffer<Char> > range;
|
||||||
|
return vformat_to<arg_formatter<range>>(
|
||||||
|
buf, to_string_view(format_str), args, internal::locale_ref(loc));
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
std::basic_string<Char> vformat(
|
||||||
|
const std::locale &loc, basic_string_view<Char> format_str,
|
||||||
|
basic_format_args<typename buffer_context<Char>::type> args) {
|
||||||
|
basic_memory_buffer<Char> buffer;
|
||||||
|
internal::vformat_to(loc, buffer, format_str, args);
|
||||||
|
return fmt::to_string(buffer);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename S, typename Char = FMT_CHAR(S)>
|
||||||
|
inline std::basic_string<Char> vformat(
|
||||||
|
const std::locale &loc, const S &format_str,
|
||||||
|
basic_format_args<typename buffer_context<Char>::type> args) {
|
||||||
|
return internal::vformat(loc, to_string_view(format_str), args);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename S, typename... Args>
|
||||||
|
inline std::basic_string<FMT_CHAR(S)> format(
|
||||||
|
const std::locale &loc, const S &format_str, const Args &... args) {
|
||||||
|
return internal::vformat(
|
||||||
|
loc, to_string_view(format_str),
|
||||||
|
*internal::checked_args<S, Args...>(format_str, args...));
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename String, typename OutputIt, typename... Args>
|
||||||
|
inline typename std::enable_if<internal::is_output_iterator<OutputIt>::value,
|
||||||
|
OutputIt>::type
|
||||||
|
vformat_to(OutputIt out, const std::locale &loc, const String &format_str,
|
||||||
|
typename format_args_t<OutputIt, FMT_CHAR(String)>::type args) {
|
||||||
|
typedef output_range<OutputIt, FMT_CHAR(String)> range;
|
||||||
|
return vformat_to<arg_formatter<range>>(
|
||||||
|
range(out), to_string_view(format_str), args, internal::locale_ref(loc));
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename OutputIt, typename S, typename... Args>
|
||||||
|
inline typename std::enable_if<
|
||||||
|
internal::is_string<S>::value &&
|
||||||
|
internal::is_output_iterator<OutputIt>::value, OutputIt>::type
|
||||||
|
format_to(OutputIt out, const std::locale &loc, const S &format_str,
|
||||||
|
const Args &... args) {
|
||||||
|
internal::check_format_string<Args...>(format_str);
|
||||||
|
typedef typename format_context_t<OutputIt, FMT_CHAR(S)>::type context;
|
||||||
|
format_arg_store<context, Args...> as{args...};
|
||||||
|
return vformat_to(out, loc, to_string_view(format_str),
|
||||||
|
basic_format_args<context>(as));
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_END_NAMESPACE
|
||||||
|
|
||||||
|
#endif // FMT_LOCALE_H_
|
153
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/ostream.h
vendored
Normal file
153
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/ostream.h
vendored
Normal file
@ -0,0 +1,153 @@
|
|||||||
|
// Formatting library for C++ - std::ostream support
|
||||||
|
//
|
||||||
|
// Copyright (c) 2012 - present, Victor Zverovich
|
||||||
|
// All rights reserved.
|
||||||
|
//
|
||||||
|
// For the license information refer to format.h.
|
||||||
|
|
||||||
|
#ifndef FMT_OSTREAM_H_
|
||||||
|
#define FMT_OSTREAM_H_
|
||||||
|
|
||||||
|
#include "format.h"
|
||||||
|
#include <ostream>
|
||||||
|
|
||||||
|
FMT_BEGIN_NAMESPACE
|
||||||
|
namespace internal {
|
||||||
|
|
||||||
|
template <class Char>
|
||||||
|
class formatbuf : public std::basic_streambuf<Char> {
|
||||||
|
private:
|
||||||
|
typedef typename std::basic_streambuf<Char>::int_type int_type;
|
||||||
|
typedef typename std::basic_streambuf<Char>::traits_type traits_type;
|
||||||
|
|
||||||
|
basic_buffer<Char> &buffer_;
|
||||||
|
|
||||||
|
public:
|
||||||
|
formatbuf(basic_buffer<Char> &buffer) : buffer_(buffer) {}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
// The put-area is actually always empty. This makes the implementation
|
||||||
|
// simpler and has the advantage that the streambuf and the buffer are always
|
||||||
|
// in sync and sputc never writes into uninitialized memory. The obvious
|
||||||
|
// disadvantage is that each call to sputc always results in a (virtual) call
|
||||||
|
// to overflow. There is no disadvantage here for sputn since this always
|
||||||
|
// results in a call to xsputn.
|
||||||
|
|
||||||
|
int_type overflow(int_type ch = traits_type::eof()) FMT_OVERRIDE {
|
||||||
|
if (!traits_type::eq_int_type(ch, traits_type::eof()))
|
||||||
|
buffer_.push_back(static_cast<Char>(ch));
|
||||||
|
return ch;
|
||||||
|
}
|
||||||
|
|
||||||
|
std::streamsize xsputn(const Char *s, std::streamsize count) FMT_OVERRIDE {
|
||||||
|
buffer_.append(s, s + count);
|
||||||
|
return count;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
struct test_stream : std::basic_ostream<Char> {
|
||||||
|
private:
|
||||||
|
struct null;
|
||||||
|
// Hide all operator<< from std::basic_ostream<Char>.
|
||||||
|
void operator<<(null);
|
||||||
|
};
|
||||||
|
|
||||||
|
// Checks if T has a user-defined operator<< (e.g. not a member of std::ostream).
|
||||||
|
template <typename T, typename Char>
|
||||||
|
class is_streamable {
|
||||||
|
private:
|
||||||
|
template <typename U>
|
||||||
|
static decltype(
|
||||||
|
internal::declval<test_stream<Char>&>()
|
||||||
|
<< internal::declval<U>(), std::true_type()) test(int);
|
||||||
|
|
||||||
|
template <typename>
|
||||||
|
static std::false_type test(...);
|
||||||
|
|
||||||
|
typedef decltype(test<T>(0)) result;
|
||||||
|
|
||||||
|
public:
|
||||||
|
static const bool value = result::value;
|
||||||
|
};
|
||||||
|
|
||||||
|
// Write the content of buf to os.
|
||||||
|
template <typename Char>
|
||||||
|
void write(std::basic_ostream<Char> &os, basic_buffer<Char> &buf) {
|
||||||
|
const Char *data = buf.data();
|
||||||
|
typedef std::make_unsigned<std::streamsize>::type UnsignedStreamSize;
|
||||||
|
UnsignedStreamSize size = buf.size();
|
||||||
|
UnsignedStreamSize max_size =
|
||||||
|
internal::to_unsigned((std::numeric_limits<std::streamsize>::max)());
|
||||||
|
do {
|
||||||
|
UnsignedStreamSize n = size <= max_size ? size : max_size;
|
||||||
|
os.write(data, static_cast<std::streamsize>(n));
|
||||||
|
data += n;
|
||||||
|
size -= n;
|
||||||
|
} while (size != 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename Char, typename T>
|
||||||
|
void format_value(basic_buffer<Char> &buffer, const T &value) {
|
||||||
|
internal::formatbuf<Char> format_buf(buffer);
|
||||||
|
std::basic_ostream<Char> output(&format_buf);
|
||||||
|
output.exceptions(std::ios_base::failbit | std::ios_base::badbit);
|
||||||
|
output << value;
|
||||||
|
buffer.resize(buffer.size());
|
||||||
|
}
|
||||||
|
} // namespace internal
|
||||||
|
|
||||||
|
// Disable conversion to int if T has an overloaded operator<< which is a free
|
||||||
|
// function (not a member of std::ostream).
|
||||||
|
template <typename T, typename Char>
|
||||||
|
struct convert_to_int<T, Char, void> {
|
||||||
|
static const bool value =
|
||||||
|
convert_to_int<T, Char, int>::value &&
|
||||||
|
!internal::is_streamable<T, Char>::value;
|
||||||
|
};
|
||||||
|
|
||||||
|
// Formats an object of type T that has an overloaded ostream operator<<.
|
||||||
|
template <typename T, typename Char>
|
||||||
|
struct formatter<T, Char,
|
||||||
|
typename std::enable_if<
|
||||||
|
internal::is_streamable<T, Char>::value &&
|
||||||
|
!internal::format_type<
|
||||||
|
typename buffer_context<Char>::type, T>::value>::type>
|
||||||
|
: formatter<basic_string_view<Char>, Char> {
|
||||||
|
|
||||||
|
template <typename Context>
|
||||||
|
auto format(const T &value, Context &ctx) -> decltype(ctx.out()) {
|
||||||
|
basic_memory_buffer<Char> buffer;
|
||||||
|
internal::format_value(buffer, value);
|
||||||
|
basic_string_view<Char> str(buffer.data(), buffer.size());
|
||||||
|
return formatter<basic_string_view<Char>, Char>::format(str, ctx);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
inline void vprint(std::basic_ostream<Char> &os,
|
||||||
|
basic_string_view<Char> format_str,
|
||||||
|
basic_format_args<typename buffer_context<Char>::type> args) {
|
||||||
|
basic_memory_buffer<Char> buffer;
|
||||||
|
internal::vformat_to(buffer, format_str, args);
|
||||||
|
internal::write(os, buffer);
|
||||||
|
}
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
Prints formatted data to the stream *os*.
|
||||||
|
|
||||||
|
**Example**::
|
||||||
|
|
||||||
|
fmt::print(cerr, "Don't {}!", "panic");
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
template <typename S, typename... Args>
|
||||||
|
inline typename std::enable_if<internal::is_string<S>::value>::type
|
||||||
|
print(std::basic_ostream<FMT_CHAR(S)> &os, const S &format_str,
|
||||||
|
const Args & ... args) {
|
||||||
|
internal::checked_args<S, Args...> ca(format_str, args...);
|
||||||
|
vprint(os, to_string_view(format_str), *ca);
|
||||||
|
}
|
||||||
|
FMT_END_NAMESPACE
|
||||||
|
|
||||||
|
#endif // FMT_OSTREAM_H_
|
324
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/posix.h
vendored
Normal file
324
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/posix.h
vendored
Normal file
@ -0,0 +1,324 @@
|
|||||||
|
// A C++ interface to POSIX functions.
|
||||||
|
//
|
||||||
|
// Copyright (c) 2012 - 2016, Victor Zverovich
|
||||||
|
// All rights reserved.
|
||||||
|
//
|
||||||
|
// For the license information refer to format.h.
|
||||||
|
|
||||||
|
#ifndef FMT_POSIX_H_
|
||||||
|
#define FMT_POSIX_H_
|
||||||
|
|
||||||
|
#if defined(__MINGW32__) || defined(__CYGWIN__)
|
||||||
|
// Workaround MinGW bug https://sourceforge.net/p/mingw/bugs/2024/.
|
||||||
|
# undef __STRICT_ANSI__
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include <errno.h>
|
||||||
|
#include <fcntl.h> // for O_RDONLY
|
||||||
|
#include <locale.h> // for locale_t
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <stdlib.h> // for strtod_l
|
||||||
|
|
||||||
|
#include <cstddef>
|
||||||
|
|
||||||
|
#if defined __APPLE__ || defined(__FreeBSD__)
|
||||||
|
# include <xlocale.h> // for LC_NUMERIC_MASK on OS X
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "format.h"
|
||||||
|
|
||||||
|
#ifndef FMT_POSIX
|
||||||
|
# if defined(_WIN32) && !defined(__MINGW32__)
|
||||||
|
// Fix warnings about deprecated symbols.
|
||||||
|
# define FMT_POSIX(call) _##call
|
||||||
|
# else
|
||||||
|
# define FMT_POSIX(call) call
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Calls to system functions are wrapped in FMT_SYSTEM for testability.
|
||||||
|
#ifdef FMT_SYSTEM
|
||||||
|
# define FMT_POSIX_CALL(call) FMT_SYSTEM(call)
|
||||||
|
#else
|
||||||
|
# define FMT_SYSTEM(call) call
|
||||||
|
# ifdef _WIN32
|
||||||
|
// Fix warnings about deprecated symbols.
|
||||||
|
# define FMT_POSIX_CALL(call) ::_##call
|
||||||
|
# else
|
||||||
|
# define FMT_POSIX_CALL(call) ::call
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Retries the expression while it evaluates to error_result and errno
|
||||||
|
// equals to EINTR.
|
||||||
|
#ifndef _WIN32
|
||||||
|
# define FMT_RETRY_VAL(result, expression, error_result) \
|
||||||
|
do { \
|
||||||
|
result = (expression); \
|
||||||
|
} while (result == error_result && errno == EINTR)
|
||||||
|
#else
|
||||||
|
# define FMT_RETRY_VAL(result, expression, error_result) result = (expression)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define FMT_RETRY(result, expression) FMT_RETRY_VAL(result, expression, -1)
|
||||||
|
|
||||||
|
FMT_BEGIN_NAMESPACE
|
||||||
|
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
A reference to a null-terminated string. It can be constructed from a C
|
||||||
|
string or ``std::string``.
|
||||||
|
|
||||||
|
You can use one of the following typedefs for common character types:
|
||||||
|
|
||||||
|
+---------------+-----------------------------+
|
||||||
|
| Type | Definition |
|
||||||
|
+===============+=============================+
|
||||||
|
| cstring_view | basic_cstring_view<char> |
|
||||||
|
+---------------+-----------------------------+
|
||||||
|
| wcstring_view | basic_cstring_view<wchar_t> |
|
||||||
|
+---------------+-----------------------------+
|
||||||
|
|
||||||
|
This class is most useful as a parameter type to allow passing
|
||||||
|
different types of strings to a function, for example::
|
||||||
|
|
||||||
|
template <typename... Args>
|
||||||
|
std::string format(cstring_view format_str, const Args & ... args);
|
||||||
|
|
||||||
|
format("{}", 42);
|
||||||
|
format(std::string("{}"), 42);
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
template <typename Char>
|
||||||
|
class basic_cstring_view {
|
||||||
|
private:
|
||||||
|
const Char *data_;
|
||||||
|
|
||||||
|
public:
|
||||||
|
/** Constructs a string reference object from a C string. */
|
||||||
|
basic_cstring_view(const Char *s) : data_(s) {}
|
||||||
|
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
Constructs a string reference from an ``std::string`` object.
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
basic_cstring_view(const std::basic_string<Char> &s) : data_(s.c_str()) {}
|
||||||
|
|
||||||
|
/** Returns the pointer to a C string. */
|
||||||
|
const Char *c_str() const { return data_; }
|
||||||
|
};
|
||||||
|
|
||||||
|
typedef basic_cstring_view<char> cstring_view;
|
||||||
|
typedef basic_cstring_view<wchar_t> wcstring_view;
|
||||||
|
|
||||||
|
// An error code.
|
||||||
|
class error_code {
|
||||||
|
private:
|
||||||
|
int value_;
|
||||||
|
|
||||||
|
public:
|
||||||
|
explicit error_code(int value = 0) FMT_NOEXCEPT : value_(value) {}
|
||||||
|
|
||||||
|
int get() const FMT_NOEXCEPT { return value_; }
|
||||||
|
};
|
||||||
|
|
||||||
|
// A buffered file.
|
||||||
|
class buffered_file {
|
||||||
|
private:
|
||||||
|
FILE *file_;
|
||||||
|
|
||||||
|
friend class file;
|
||||||
|
|
||||||
|
explicit buffered_file(FILE *f) : file_(f) {}
|
||||||
|
|
||||||
|
public:
|
||||||
|
// Constructs a buffered_file object which doesn't represent any file.
|
||||||
|
buffered_file() FMT_NOEXCEPT : file_(FMT_NULL) {}
|
||||||
|
|
||||||
|
// Destroys the object closing the file it represents if any.
|
||||||
|
FMT_API ~buffered_file() FMT_NOEXCEPT;
|
||||||
|
|
||||||
|
private:
|
||||||
|
buffered_file(const buffered_file &) = delete;
|
||||||
|
void operator=(const buffered_file &) = delete;
|
||||||
|
|
||||||
|
|
||||||
|
public:
|
||||||
|
buffered_file(buffered_file &&other) FMT_NOEXCEPT : file_(other.file_) {
|
||||||
|
other.file_ = FMT_NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
buffered_file& operator=(buffered_file &&other) {
|
||||||
|
close();
|
||||||
|
file_ = other.file_;
|
||||||
|
other.file_ = FMT_NULL;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Opens a file.
|
||||||
|
FMT_API buffered_file(cstring_view filename, cstring_view mode);
|
||||||
|
|
||||||
|
// Closes the file.
|
||||||
|
FMT_API void close();
|
||||||
|
|
||||||
|
// Returns the pointer to a FILE object representing this file.
|
||||||
|
FILE *get() const FMT_NOEXCEPT { return file_; }
|
||||||
|
|
||||||
|
// We place parentheses around fileno to workaround a bug in some versions
|
||||||
|
// of MinGW that define fileno as a macro.
|
||||||
|
FMT_API int (fileno)() const;
|
||||||
|
|
||||||
|
void vprint(string_view format_str, format_args args) {
|
||||||
|
fmt::vprint(file_, format_str, args);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename... Args>
|
||||||
|
inline void print(string_view format_str, const Args & ... args) {
|
||||||
|
vprint(format_str, make_format_args(args...));
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
// A file. Closed file is represented by a file object with descriptor -1.
|
||||||
|
// Methods that are not declared with FMT_NOEXCEPT may throw
|
||||||
|
// fmt::system_error in case of failure. Note that some errors such as
|
||||||
|
// closing the file multiple times will cause a crash on Windows rather
|
||||||
|
// than an exception. You can get standard behavior by overriding the
|
||||||
|
// invalid parameter handler with _set_invalid_parameter_handler.
|
||||||
|
class file {
|
||||||
|
private:
|
||||||
|
int fd_; // File descriptor.
|
||||||
|
|
||||||
|
// Constructs a file object with a given descriptor.
|
||||||
|
explicit file(int fd) : fd_(fd) {}
|
||||||
|
|
||||||
|
public:
|
||||||
|
// Possible values for the oflag argument to the constructor.
|
||||||
|
enum {
|
||||||
|
RDONLY = FMT_POSIX(O_RDONLY), // Open for reading only.
|
||||||
|
WRONLY = FMT_POSIX(O_WRONLY), // Open for writing only.
|
||||||
|
RDWR = FMT_POSIX(O_RDWR) // Open for reading and writing.
|
||||||
|
};
|
||||||
|
|
||||||
|
// Constructs a file object which doesn't represent any file.
|
||||||
|
file() FMT_NOEXCEPT : fd_(-1) {}
|
||||||
|
|
||||||
|
// Opens a file and constructs a file object representing this file.
|
||||||
|
FMT_API file(cstring_view path, int oflag);
|
||||||
|
|
||||||
|
private:
|
||||||
|
file(const file &) = delete;
|
||||||
|
void operator=(const file &) = delete;
|
||||||
|
|
||||||
|
public:
|
||||||
|
file(file &&other) FMT_NOEXCEPT : fd_(other.fd_) {
|
||||||
|
other.fd_ = -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
file& operator=(file &&other) {
|
||||||
|
close();
|
||||||
|
fd_ = other.fd_;
|
||||||
|
other.fd_ = -1;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Destroys the object closing the file it represents if any.
|
||||||
|
FMT_API ~file() FMT_NOEXCEPT;
|
||||||
|
|
||||||
|
// Returns the file descriptor.
|
||||||
|
int descriptor() const FMT_NOEXCEPT { return fd_; }
|
||||||
|
|
||||||
|
// Closes the file.
|
||||||
|
FMT_API void close();
|
||||||
|
|
||||||
|
// Returns the file size. The size has signed type for consistency with
|
||||||
|
// stat::st_size.
|
||||||
|
FMT_API long long size() const;
|
||||||
|
|
||||||
|
// Attempts to read count bytes from the file into the specified buffer.
|
||||||
|
FMT_API std::size_t read(void *buffer, std::size_t count);
|
||||||
|
|
||||||
|
// Attempts to write count bytes from the specified buffer to the file.
|
||||||
|
FMT_API std::size_t write(const void *buffer, std::size_t count);
|
||||||
|
|
||||||
|
// Duplicates a file descriptor with the dup function and returns
|
||||||
|
// the duplicate as a file object.
|
||||||
|
FMT_API static file dup(int fd);
|
||||||
|
|
||||||
|
// Makes fd be the copy of this file descriptor, closing fd first if
|
||||||
|
// necessary.
|
||||||
|
FMT_API void dup2(int fd);
|
||||||
|
|
||||||
|
// Makes fd be the copy of this file descriptor, closing fd first if
|
||||||
|
// necessary.
|
||||||
|
FMT_API void dup2(int fd, error_code &ec) FMT_NOEXCEPT;
|
||||||
|
|
||||||
|
// Creates a pipe setting up read_end and write_end file objects for reading
|
||||||
|
// and writing respectively.
|
||||||
|
FMT_API static void pipe(file &read_end, file &write_end);
|
||||||
|
|
||||||
|
// Creates a buffered_file object associated with this file and detaches
|
||||||
|
// this file object from the file.
|
||||||
|
FMT_API buffered_file fdopen(const char *mode);
|
||||||
|
};
|
||||||
|
|
||||||
|
// Returns the memory page size.
|
||||||
|
long getpagesize();
|
||||||
|
|
||||||
|
#if (defined(LC_NUMERIC_MASK) || defined(_MSC_VER)) && \
|
||||||
|
!defined(__ANDROID__) && !defined(__CYGWIN__) && !defined(__OpenBSD__) && \
|
||||||
|
!defined(__NEWLIB_H__)
|
||||||
|
# define FMT_LOCALE
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef FMT_LOCALE
|
||||||
|
// A "C" numeric locale.
|
||||||
|
class Locale {
|
||||||
|
private:
|
||||||
|
# ifdef _MSC_VER
|
||||||
|
typedef _locale_t locale_t;
|
||||||
|
|
||||||
|
enum { LC_NUMERIC_MASK = LC_NUMERIC };
|
||||||
|
|
||||||
|
static locale_t newlocale(int category_mask, const char *locale, locale_t) {
|
||||||
|
return _create_locale(category_mask, locale);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void freelocale(locale_t locale) {
|
||||||
|
_free_locale(locale);
|
||||||
|
}
|
||||||
|
|
||||||
|
static double strtod_l(const char *nptr, char **endptr, _locale_t locale) {
|
||||||
|
return _strtod_l(nptr, endptr, locale);
|
||||||
|
}
|
||||||
|
# endif
|
||||||
|
|
||||||
|
locale_t locale_;
|
||||||
|
|
||||||
|
Locale(const Locale &) = delete;
|
||||||
|
void operator=(const Locale &) = delete;
|
||||||
|
|
||||||
|
public:
|
||||||
|
typedef locale_t Type;
|
||||||
|
|
||||||
|
Locale() : locale_(newlocale(LC_NUMERIC_MASK, "C", FMT_NULL)) {
|
||||||
|
if (!locale_)
|
||||||
|
FMT_THROW(system_error(errno, "cannot create locale"));
|
||||||
|
}
|
||||||
|
~Locale() { freelocale(locale_); }
|
||||||
|
|
||||||
|
Type get() const { return locale_; }
|
||||||
|
|
||||||
|
// Converts string to floating-point number and advances str past the end
|
||||||
|
// of the parsed input.
|
||||||
|
double strtod(const char *&str) const {
|
||||||
|
char *end = FMT_NULL;
|
||||||
|
double result = strtod_l(str, &end, locale_);
|
||||||
|
str = end;
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
#endif // FMT_LOCALE
|
||||||
|
FMT_END_NAMESPACE
|
||||||
|
|
||||||
|
#endif // FMT_POSIX_H_
|
855
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/printf.h
vendored
Normal file
855
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/printf.h
vendored
Normal file
@ -0,0 +1,855 @@
|
|||||||
|
// Formatting library for C++
|
||||||
|
//
|
||||||
|
// Copyright (c) 2012 - 2016, Victor Zverovich
|
||||||
|
// All rights reserved.
|
||||||
|
//
|
||||||
|
// For the license information refer to format.h.
|
||||||
|
|
||||||
|
#ifndef FMT_PRINTF_H_
|
||||||
|
#define FMT_PRINTF_H_
|
||||||
|
|
||||||
|
#include <algorithm> // std::fill_n
|
||||||
|
#include <limits> // std::numeric_limits
|
||||||
|
|
||||||
|
#include "ostream.h"
|
||||||
|
|
||||||
|
FMT_BEGIN_NAMESPACE
|
||||||
|
namespace internal {
|
||||||
|
|
||||||
|
// An iterator that produces a null terminator on *end. This simplifies parsing
|
||||||
|
// and allows comparing the performance of processing a null-terminated string
|
||||||
|
// vs string_view.
|
||||||
|
template <typename Char>
|
||||||
|
class null_terminating_iterator {
|
||||||
|
public:
|
||||||
|
typedef std::ptrdiff_t difference_type;
|
||||||
|
typedef Char value_type;
|
||||||
|
typedef const Char* pointer;
|
||||||
|
typedef const Char& reference;
|
||||||
|
typedef std::random_access_iterator_tag iterator_category;
|
||||||
|
|
||||||
|
null_terminating_iterator() : ptr_(0), end_(0) {}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR null_terminating_iterator(const Char *ptr, const Char *end)
|
||||||
|
: ptr_(ptr), end_(end) {}
|
||||||
|
|
||||||
|
template <typename Range>
|
||||||
|
FMT_CONSTEXPR explicit null_terminating_iterator(const Range &r)
|
||||||
|
: ptr_(r.begin()), end_(r.end()) {}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR null_terminating_iterator &operator=(const Char *ptr) {
|
||||||
|
assert(ptr <= end_);
|
||||||
|
ptr_ = ptr;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR Char operator*() const {
|
||||||
|
return ptr_ != end_ ? *ptr_ : Char();
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR null_terminating_iterator operator++() {
|
||||||
|
++ptr_;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR null_terminating_iterator operator++(int) {
|
||||||
|
null_terminating_iterator result(*this);
|
||||||
|
++ptr_;
|
||||||
|
return result;
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR null_terminating_iterator operator--() {
|
||||||
|
--ptr_;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR null_terminating_iterator operator+(difference_type n) {
|
||||||
|
return null_terminating_iterator(ptr_ + n, end_);
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR null_terminating_iterator operator-(difference_type n) {
|
||||||
|
return null_terminating_iterator(ptr_ - n, end_);
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR null_terminating_iterator operator+=(difference_type n) {
|
||||||
|
ptr_ += n;
|
||||||
|
return *this;
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR difference_type operator-(
|
||||||
|
null_terminating_iterator other) const {
|
||||||
|
return ptr_ - other.ptr_;
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR bool operator!=(null_terminating_iterator other) const {
|
||||||
|
return ptr_ != other.ptr_;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool operator>=(null_terminating_iterator other) const {
|
||||||
|
return ptr_ >= other.ptr_;
|
||||||
|
}
|
||||||
|
|
||||||
|
// This should be a friend specialization pointer_from<Char> but the latter
|
||||||
|
// doesn't compile by gcc 5.1 due to a compiler bug.
|
||||||
|
template <typename CharT>
|
||||||
|
friend FMT_CONSTEXPR_DECL const CharT *pointer_from(
|
||||||
|
null_terminating_iterator<CharT> it);
|
||||||
|
|
||||||
|
private:
|
||||||
|
const Char *ptr_;
|
||||||
|
const Char *end_;
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
FMT_CONSTEXPR const T *pointer_from(const T *p) { return p; }
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
FMT_CONSTEXPR const Char *pointer_from(null_terminating_iterator<Char> it) {
|
||||||
|
return it.ptr_;
|
||||||
|
}
|
||||||
|
|
||||||
|
// DEPRECATED: Parses the input as an unsigned integer. This function assumes
|
||||||
|
// that the first character is a digit and presence of a non-digit character at
|
||||||
|
// the end.
|
||||||
|
// it: an iterator pointing to the beginning of the input range.
|
||||||
|
template <typename Iterator, typename ErrorHandler>
|
||||||
|
FMT_CONSTEXPR unsigned parse_nonnegative_int(Iterator &it, ErrorHandler &&eh) {
|
||||||
|
assert('0' <= *it && *it <= '9');
|
||||||
|
if (*it == '0') {
|
||||||
|
++it;
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
unsigned value = 0;
|
||||||
|
// Convert to unsigned to prevent a warning.
|
||||||
|
unsigned max_int = (std::numeric_limits<int>::max)();
|
||||||
|
unsigned big = max_int / 10;
|
||||||
|
do {
|
||||||
|
// Check for overflow.
|
||||||
|
if (value > big) {
|
||||||
|
value = max_int + 1;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
value = value * 10 + unsigned(*it - '0');
|
||||||
|
// Workaround for MSVC "setup_exception stack overflow" error:
|
||||||
|
auto next = it;
|
||||||
|
++next;
|
||||||
|
it = next;
|
||||||
|
} while ('0' <= *it && *it <= '9');
|
||||||
|
if (value > max_int)
|
||||||
|
eh.on_error("number is too big");
|
||||||
|
return value;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Checks if a value fits in int - used to avoid warnings about comparing
|
||||||
|
// signed and unsigned integers.
|
||||||
|
template <bool IsSigned>
|
||||||
|
struct int_checker {
|
||||||
|
template <typename T>
|
||||||
|
static bool fits_in_int(T value) {
|
||||||
|
unsigned max = std::numeric_limits<int>::max();
|
||||||
|
return value <= max;
|
||||||
|
}
|
||||||
|
static bool fits_in_int(bool) { return true; }
|
||||||
|
};
|
||||||
|
|
||||||
|
template <>
|
||||||
|
struct int_checker<true> {
|
||||||
|
template <typename T>
|
||||||
|
static bool fits_in_int(T value) {
|
||||||
|
return value >= std::numeric_limits<int>::min() &&
|
||||||
|
value <= std::numeric_limits<int>::max();
|
||||||
|
}
|
||||||
|
static bool fits_in_int(int) { return true; }
|
||||||
|
};
|
||||||
|
|
||||||
|
class printf_precision_handler: public function<int> {
|
||||||
|
public:
|
||||||
|
template <typename T>
|
||||||
|
typename std::enable_if<std::is_integral<T>::value, int>::type
|
||||||
|
operator()(T value) {
|
||||||
|
if (!int_checker<std::numeric_limits<T>::is_signed>::fits_in_int(value))
|
||||||
|
FMT_THROW(format_error("number is too big"));
|
||||||
|
return static_cast<int>(value);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
typename std::enable_if<!std::is_integral<T>::value, int>::type operator()(T) {
|
||||||
|
FMT_THROW(format_error("precision is not integer"));
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
// An argument visitor that returns true iff arg is a zero integer.
|
||||||
|
class is_zero_int: public function<bool> {
|
||||||
|
public:
|
||||||
|
template <typename T>
|
||||||
|
typename std::enable_if<std::is_integral<T>::value, bool>::type
|
||||||
|
operator()(T value) { return value == 0; }
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
typename std::enable_if<!std::is_integral<T>::value, bool>::type
|
||||||
|
operator()(T) { return false; }
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
struct make_unsigned_or_bool : std::make_unsigned<T> {};
|
||||||
|
|
||||||
|
template <>
|
||||||
|
struct make_unsigned_or_bool<bool> {
|
||||||
|
typedef bool type;
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename T, typename Context>
|
||||||
|
class arg_converter: public function<void> {
|
||||||
|
private:
|
||||||
|
typedef typename Context::char_type Char;
|
||||||
|
|
||||||
|
basic_format_arg<Context> &arg_;
|
||||||
|
typename Context::char_type type_;
|
||||||
|
|
||||||
|
public:
|
||||||
|
arg_converter(basic_format_arg<Context> &arg, Char type)
|
||||||
|
: arg_(arg), type_(type) {}
|
||||||
|
|
||||||
|
void operator()(bool value) {
|
||||||
|
if (type_ != 's')
|
||||||
|
operator()<bool>(value);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename U>
|
||||||
|
typename std::enable_if<std::is_integral<U>::value>::type
|
||||||
|
operator()(U value) {
|
||||||
|
bool is_signed = type_ == 'd' || type_ == 'i';
|
||||||
|
typedef typename std::conditional<
|
||||||
|
std::is_same<T, void>::value, U, T>::type TargetType;
|
||||||
|
if (const_check(sizeof(TargetType) <= sizeof(int))) {
|
||||||
|
// Extra casts are used to silence warnings.
|
||||||
|
if (is_signed) {
|
||||||
|
arg_ = internal::make_arg<Context>(
|
||||||
|
static_cast<int>(static_cast<TargetType>(value)));
|
||||||
|
} else {
|
||||||
|
typedef typename make_unsigned_or_bool<TargetType>::type Unsigned;
|
||||||
|
arg_ = internal::make_arg<Context>(
|
||||||
|
static_cast<unsigned>(static_cast<Unsigned>(value)));
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
if (is_signed) {
|
||||||
|
// glibc's printf doesn't sign extend arguments of smaller types:
|
||||||
|
// std::printf("%lld", -42); // prints "4294967254"
|
||||||
|
// but we don't have to do the same because it's a UB.
|
||||||
|
arg_ = internal::make_arg<Context>(static_cast<long long>(value));
|
||||||
|
} else {
|
||||||
|
arg_ = internal::make_arg<Context>(
|
||||||
|
static_cast<typename make_unsigned_or_bool<U>::type>(value));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename U>
|
||||||
|
typename std::enable_if<!std::is_integral<U>::value>::type operator()(U) {
|
||||||
|
// No coversion needed for non-integral types.
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
// Converts an integer argument to T for printf, if T is an integral type.
|
||||||
|
// If T is void, the argument is converted to corresponding signed or unsigned
|
||||||
|
// type depending on the type specifier: 'd' and 'i' - signed, other -
|
||||||
|
// unsigned).
|
||||||
|
template <typename T, typename Context, typename Char>
|
||||||
|
void convert_arg(basic_format_arg<Context> &arg, Char type) {
|
||||||
|
visit_format_arg(arg_converter<T, Context>(arg, type), arg);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Converts an integer argument to char for printf.
|
||||||
|
template <typename Context>
|
||||||
|
class char_converter: public function<void> {
|
||||||
|
private:
|
||||||
|
basic_format_arg<Context> &arg_;
|
||||||
|
|
||||||
|
public:
|
||||||
|
explicit char_converter(basic_format_arg<Context> &arg) : arg_(arg) {}
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
typename std::enable_if<std::is_integral<T>::value>::type
|
||||||
|
operator()(T value) {
|
||||||
|
typedef typename Context::char_type Char;
|
||||||
|
arg_ = internal::make_arg<Context>(static_cast<Char>(value));
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
typename std::enable_if<!std::is_integral<T>::value>::type operator()(T) {
|
||||||
|
// No coversion needed for non-integral types.
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
// Checks if an argument is a valid printf width specifier and sets
|
||||||
|
// left alignment if it is negative.
|
||||||
|
template <typename Char>
|
||||||
|
class printf_width_handler: public function<unsigned> {
|
||||||
|
private:
|
||||||
|
typedef basic_format_specs<Char> format_specs;
|
||||||
|
|
||||||
|
format_specs &spec_;
|
||||||
|
|
||||||
|
public:
|
||||||
|
explicit printf_width_handler(format_specs &spec) : spec_(spec) {}
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
typename std::enable_if<std::is_integral<T>::value, unsigned>::type
|
||||||
|
operator()(T value) {
|
||||||
|
typedef typename internal::int_traits<T>::main_type UnsignedType;
|
||||||
|
UnsignedType width = static_cast<UnsignedType>(value);
|
||||||
|
if (internal::is_negative(value)) {
|
||||||
|
spec_.align_ = ALIGN_LEFT;
|
||||||
|
width = 0 - width;
|
||||||
|
}
|
||||||
|
unsigned int_max = std::numeric_limits<int>::max();
|
||||||
|
if (width > int_max)
|
||||||
|
FMT_THROW(format_error("number is too big"));
|
||||||
|
return static_cast<unsigned>(width);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
typename std::enable_if<!std::is_integral<T>::value, unsigned>::type
|
||||||
|
operator()(T) {
|
||||||
|
FMT_THROW(format_error("width is not integer"));
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename Char, typename Context>
|
||||||
|
void printf(basic_buffer<Char> &buf, basic_string_view<Char> format,
|
||||||
|
basic_format_args<Context> args) {
|
||||||
|
Context(std::back_inserter(buf), format, args).format();
|
||||||
|
}
|
||||||
|
} // namespace internal
|
||||||
|
|
||||||
|
using internal::printf; // For printing into memory_buffer.
|
||||||
|
|
||||||
|
template <typename Range>
|
||||||
|
class printf_arg_formatter;
|
||||||
|
|
||||||
|
template <
|
||||||
|
typename OutputIt, typename Char,
|
||||||
|
typename ArgFormatter =
|
||||||
|
printf_arg_formatter<back_insert_range<internal::basic_buffer<Char>>>>
|
||||||
|
class basic_printf_context;
|
||||||
|
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
The ``printf`` argument formatter.
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
template <typename Range>
|
||||||
|
class printf_arg_formatter:
|
||||||
|
public internal::function<
|
||||||
|
typename internal::arg_formatter_base<Range>::iterator>,
|
||||||
|
public internal::arg_formatter_base<Range> {
|
||||||
|
private:
|
||||||
|
typedef typename Range::value_type char_type;
|
||||||
|
typedef decltype(internal::declval<Range>().begin()) iterator;
|
||||||
|
typedef internal::arg_formatter_base<Range> base;
|
||||||
|
typedef basic_printf_context<iterator, char_type> context_type;
|
||||||
|
|
||||||
|
context_type &context_;
|
||||||
|
|
||||||
|
void write_null_pointer(char) {
|
||||||
|
this->spec()->type = 0;
|
||||||
|
this->write("(nil)");
|
||||||
|
}
|
||||||
|
|
||||||
|
void write_null_pointer(wchar_t) {
|
||||||
|
this->spec()->type = 0;
|
||||||
|
this->write(L"(nil)");
|
||||||
|
}
|
||||||
|
|
||||||
|
public:
|
||||||
|
typedef typename base::format_specs format_specs;
|
||||||
|
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
Constructs an argument formatter object.
|
||||||
|
*buffer* is a reference to the output buffer and *spec* contains format
|
||||||
|
specifier information for standard argument types.
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
printf_arg_formatter(internal::basic_buffer<char_type> &buffer,
|
||||||
|
format_specs &spec, context_type &ctx)
|
||||||
|
: base(back_insert_range<internal::basic_buffer<char_type>>(buffer), &spec,
|
||||||
|
ctx.locale()),
|
||||||
|
context_(ctx) {}
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
typename std::enable_if<std::is_integral<T>::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<T, bool>::value) {
|
||||||
|
format_specs &fmt_spec = *this->spec();
|
||||||
|
if (fmt_spec.type != 's')
|
||||||
|
return base::operator()(value ? 1 : 0);
|
||||||
|
fmt_spec.type = 0;
|
||||||
|
this->write(value != 0);
|
||||||
|
} else if (std::is_same<T, char_type>::value) {
|
||||||
|
format_specs &fmt_spec = *this->spec();
|
||||||
|
if (fmt_spec.type && fmt_spec.type != 'c')
|
||||||
|
return (*this)(static_cast<int>(value));
|
||||||
|
fmt_spec.flags = 0;
|
||||||
|
fmt_spec.align_ = ALIGN_RIGHT;
|
||||||
|
return base::operator()(value);
|
||||||
|
} else {
|
||||||
|
return base::operator()(value);
|
||||||
|
}
|
||||||
|
return this->out();
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
typename std::enable_if<std::is_floating_point<T>::value, iterator>::type
|
||||||
|
operator()(T value) {
|
||||||
|
return base::operator()(value);
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Formats a null-terminated C string. */
|
||||||
|
iterator operator()(const char *value) {
|
||||||
|
if (value)
|
||||||
|
base::operator()(value);
|
||||||
|
else if (this->spec()->type == 'p')
|
||||||
|
write_null_pointer(char_type());
|
||||||
|
else
|
||||||
|
this->write("(null)");
|
||||||
|
return this->out();
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Formats a null-terminated wide C string. */
|
||||||
|
iterator operator()(const wchar_t *value) {
|
||||||
|
if (value)
|
||||||
|
base::operator()(value);
|
||||||
|
else if (this->spec()->type == 'p')
|
||||||
|
write_null_pointer(char_type());
|
||||||
|
else
|
||||||
|
this->write(L"(null)");
|
||||||
|
return this->out();
|
||||||
|
}
|
||||||
|
|
||||||
|
iterator operator()(basic_string_view<char_type> value) {
|
||||||
|
return base::operator()(value);
|
||||||
|
}
|
||||||
|
|
||||||
|
iterator operator()(monostate value) {
|
||||||
|
return base::operator()(value);
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Formats a pointer. */
|
||||||
|
iterator operator()(const void *value) {
|
||||||
|
if (value)
|
||||||
|
return base::operator()(value);
|
||||||
|
this->spec()->type = 0;
|
||||||
|
write_null_pointer(char_type());
|
||||||
|
return this->out();
|
||||||
|
}
|
||||||
|
|
||||||
|
/** Formats an argument of a custom (user-defined) type. */
|
||||||
|
iterator operator()(typename basic_format_arg<context_type>::handle handle) {
|
||||||
|
handle.format(context_);
|
||||||
|
return this->out();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
struct printf_formatter {
|
||||||
|
template <typename ParseContext>
|
||||||
|
auto parse(ParseContext &ctx) -> decltype(ctx.begin()) { return ctx.begin(); }
|
||||||
|
|
||||||
|
template <typename FormatContext>
|
||||||
|
auto format(const T &value, FormatContext &ctx) -> decltype(ctx.out()) {
|
||||||
|
internal::format_value(internal::get_container(ctx.out()), value);
|
||||||
|
return ctx.out();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
/** This template formats data and writes the output to a writer. */
|
||||||
|
template <typename OutputIt, typename Char, typename ArgFormatter>
|
||||||
|
class basic_printf_context :
|
||||||
|
// Inherit publicly as a workaround for the icc bug
|
||||||
|
// https://software.intel.com/en-us/forums/intel-c-compiler/topic/783476.
|
||||||
|
public internal::context_base<
|
||||||
|
OutputIt, basic_printf_context<OutputIt, Char, ArgFormatter>, Char> {
|
||||||
|
public:
|
||||||
|
/** The character type for the output. */
|
||||||
|
typedef Char char_type;
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
struct formatter_type { typedef printf_formatter<T> type; };
|
||||||
|
|
||||||
|
private:
|
||||||
|
typedef internal::context_base<OutputIt, basic_printf_context, Char> base;
|
||||||
|
typedef typename base::format_arg format_arg;
|
||||||
|
typedef basic_format_specs<char_type> format_specs;
|
||||||
|
typedef internal::null_terminating_iterator<char_type> iterator;
|
||||||
|
|
||||||
|
void parse_flags(format_specs &spec, iterator &it);
|
||||||
|
|
||||||
|
// Returns the argument with specified index or, if arg_index is equal
|
||||||
|
// to the maximum unsigned value, the next argument.
|
||||||
|
format_arg get_arg(
|
||||||
|
iterator it,
|
||||||
|
unsigned arg_index = (std::numeric_limits<unsigned>::max)());
|
||||||
|
|
||||||
|
// Parses argument index, flags and width and returns the argument index.
|
||||||
|
unsigned parse_header(iterator &it, format_specs &spec);
|
||||||
|
|
||||||
|
public:
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
Constructs a ``printf_context`` object. References to the arguments and
|
||||||
|
the writer are stored in the context object so make sure they have
|
||||||
|
appropriate lifetimes.
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
basic_printf_context(OutputIt out, basic_string_view<char_type> format_str,
|
||||||
|
basic_format_args<basic_printf_context> args)
|
||||||
|
: base(out, format_str, args) {}
|
||||||
|
|
||||||
|
using base::parse_context;
|
||||||
|
using base::out;
|
||||||
|
using base::advance_to;
|
||||||
|
|
||||||
|
/** Formats stored arguments and writes the output to the range. */
|
||||||
|
void format();
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename OutputIt, typename Char, typename AF>
|
||||||
|
void basic_printf_context<OutputIt, Char, AF>::parse_flags(
|
||||||
|
format_specs &spec, iterator &it) {
|
||||||
|
for (;;) {
|
||||||
|
switch (*it++) {
|
||||||
|
case '-':
|
||||||
|
spec.align_ = ALIGN_LEFT;
|
||||||
|
break;
|
||||||
|
case '+':
|
||||||
|
spec.flags |= SIGN_FLAG | PLUS_FLAG;
|
||||||
|
break;
|
||||||
|
case '0':
|
||||||
|
spec.fill_ = '0';
|
||||||
|
break;
|
||||||
|
case ' ':
|
||||||
|
spec.flags |= SIGN_FLAG;
|
||||||
|
break;
|
||||||
|
case '#':
|
||||||
|
spec.flags |= HASH_FLAG;
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
--it;
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename OutputIt, typename Char, typename AF>
|
||||||
|
typename basic_printf_context<OutputIt, Char, AF>::format_arg
|
||||||
|
basic_printf_context<OutputIt, Char, AF>::get_arg(
|
||||||
|
iterator it, unsigned arg_index) {
|
||||||
|
(void)it;
|
||||||
|
if (arg_index == std::numeric_limits<unsigned>::max())
|
||||||
|
return this->do_get_arg(this->parse_context().next_arg_id());
|
||||||
|
return base::get_arg(arg_index - 1);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename OutputIt, typename Char, typename AF>
|
||||||
|
unsigned basic_printf_context<OutputIt, Char, AF>::parse_header(
|
||||||
|
iterator &it, format_specs &spec) {
|
||||||
|
unsigned arg_index = std::numeric_limits<unsigned>::max();
|
||||||
|
char_type c = *it;
|
||||||
|
if (c >= '0' && c <= '9') {
|
||||||
|
// Parse an argument index (if followed by '$') or a width possibly
|
||||||
|
// preceded with '0' flag(s).
|
||||||
|
internal::error_handler eh;
|
||||||
|
unsigned value = parse_nonnegative_int(it, eh);
|
||||||
|
if (*it == '$') { // value is an argument index
|
||||||
|
++it;
|
||||||
|
arg_index = value;
|
||||||
|
} else {
|
||||||
|
if (c == '0')
|
||||||
|
spec.fill_ = '0';
|
||||||
|
if (value != 0) {
|
||||||
|
// Nonzero value means that we parsed width and don't need to
|
||||||
|
// parse it or flags again, so return now.
|
||||||
|
spec.width_ = value;
|
||||||
|
return arg_index;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
parse_flags(spec, it);
|
||||||
|
// Parse width.
|
||||||
|
if (*it >= '0' && *it <= '9') {
|
||||||
|
internal::error_handler eh;
|
||||||
|
spec.width_ = parse_nonnegative_int(it, eh);
|
||||||
|
} else if (*it == '*') {
|
||||||
|
++it;
|
||||||
|
spec.width_ = visit_format_arg(
|
||||||
|
internal::printf_width_handler<char_type>(spec), get_arg(it));
|
||||||
|
}
|
||||||
|
return arg_index;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename OutputIt, typename Char, typename AF>
|
||||||
|
void basic_printf_context<OutputIt, Char, AF>::format() {
|
||||||
|
auto &buffer = internal::get_container(this->out());
|
||||||
|
auto start = iterator(this->parse_context());
|
||||||
|
auto it = start;
|
||||||
|
using internal::pointer_from;
|
||||||
|
while (*it) {
|
||||||
|
char_type c = *it++;
|
||||||
|
if (c != '%') continue;
|
||||||
|
if (*it == c) {
|
||||||
|
buffer.append(pointer_from(start), pointer_from(it));
|
||||||
|
start = ++it;
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
buffer.append(pointer_from(start), pointer_from(it) - 1);
|
||||||
|
|
||||||
|
format_specs spec;
|
||||||
|
spec.align_ = ALIGN_RIGHT;
|
||||||
|
|
||||||
|
// Parse argument index, flags and width.
|
||||||
|
unsigned arg_index = parse_header(it, spec);
|
||||||
|
|
||||||
|
// Parse precision.
|
||||||
|
if (*it == '.') {
|
||||||
|
++it;
|
||||||
|
if ('0' <= *it && *it <= '9') {
|
||||||
|
internal::error_handler eh;
|
||||||
|
spec.precision = static_cast<int>(parse_nonnegative_int(it, eh));
|
||||||
|
} else if (*it == '*') {
|
||||||
|
++it;
|
||||||
|
spec.precision =
|
||||||
|
visit_format_arg(internal::printf_precision_handler(), get_arg(it));
|
||||||
|
} else {
|
||||||
|
spec.precision = 0;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
format_arg arg = get_arg(it, arg_index);
|
||||||
|
if (spec.has(HASH_FLAG) && visit_format_arg(internal::is_zero_int(), arg))
|
||||||
|
spec.flags = static_cast<uint_least8_t>(spec.flags & (~internal::to_unsigned<int>(HASH_FLAG)));
|
||||||
|
if (spec.fill_ == '0') {
|
||||||
|
if (arg.is_arithmetic())
|
||||||
|
spec.align_ = ALIGN_NUMERIC;
|
||||||
|
else
|
||||||
|
spec.fill_ = ' '; // Ignore '0' flag for non-numeric types.
|
||||||
|
}
|
||||||
|
|
||||||
|
// Parse length and convert the argument to the required type.
|
||||||
|
using internal::convert_arg;
|
||||||
|
switch (*it++) {
|
||||||
|
case 'h':
|
||||||
|
if (*it == 'h')
|
||||||
|
convert_arg<signed char>(arg, *++it);
|
||||||
|
else
|
||||||
|
convert_arg<short>(arg, *it);
|
||||||
|
break;
|
||||||
|
case 'l':
|
||||||
|
if (*it == 'l')
|
||||||
|
convert_arg<long long>(arg, *++it);
|
||||||
|
else
|
||||||
|
convert_arg<long>(arg, *it);
|
||||||
|
break;
|
||||||
|
case 'j':
|
||||||
|
convert_arg<intmax_t>(arg, *it);
|
||||||
|
break;
|
||||||
|
case 'z':
|
||||||
|
convert_arg<std::size_t>(arg, *it);
|
||||||
|
break;
|
||||||
|
case 't':
|
||||||
|
convert_arg<std::ptrdiff_t>(arg, *it);
|
||||||
|
break;
|
||||||
|
case 'L':
|
||||||
|
// printf produces garbage when 'L' is omitted for long double, no
|
||||||
|
// need to do the same.
|
||||||
|
break;
|
||||||
|
default:
|
||||||
|
--it;
|
||||||
|
convert_arg<void>(arg, *it);
|
||||||
|
}
|
||||||
|
|
||||||
|
// Parse type.
|
||||||
|
if (!*it)
|
||||||
|
FMT_THROW(format_error("invalid format string"));
|
||||||
|
spec.type = static_cast<char>(*it++);
|
||||||
|
if (arg.is_integral()) {
|
||||||
|
// Normalize type.
|
||||||
|
switch (spec.type) {
|
||||||
|
case 'i': case 'u':
|
||||||
|
spec.type = 'd';
|
||||||
|
break;
|
||||||
|
case 'c':
|
||||||
|
// TODO: handle wchar_t better?
|
||||||
|
visit_format_arg(
|
||||||
|
internal::char_converter<basic_printf_context>(arg), arg);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
start = it;
|
||||||
|
|
||||||
|
// Format argument.
|
||||||
|
visit_format_arg(AF(buffer, spec, *this), arg);
|
||||||
|
}
|
||||||
|
buffer.append(pointer_from(start), pointer_from(it));
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename Buffer>
|
||||||
|
struct basic_printf_context_t {
|
||||||
|
typedef basic_printf_context<
|
||||||
|
std::back_insert_iterator<Buffer>, typename Buffer::value_type> type;
|
||||||
|
};
|
||||||
|
|
||||||
|
typedef basic_printf_context_t<internal::buffer>::type printf_context;
|
||||||
|
typedef basic_printf_context_t<internal::wbuffer>::type wprintf_context;
|
||||||
|
|
||||||
|
typedef basic_format_args<printf_context> printf_args;
|
||||||
|
typedef basic_format_args<wprintf_context> wprintf_args;
|
||||||
|
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
Constructs an `~fmt::format_arg_store` object that contains references to
|
||||||
|
arguments and can be implicitly converted to `~fmt::printf_args`.
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
template<typename... Args>
|
||||||
|
inline format_arg_store<printf_context, Args...>
|
||||||
|
make_printf_args(const Args &... args) { return {args...}; }
|
||||||
|
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
Constructs an `~fmt::format_arg_store` object that contains references to
|
||||||
|
arguments and can be implicitly converted to `~fmt::wprintf_args`.
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
template<typename... Args>
|
||||||
|
inline format_arg_store<wprintf_context, Args...>
|
||||||
|
make_wprintf_args(const Args &... args) { return {args...}; }
|
||||||
|
|
||||||
|
template <typename S, typename Char = FMT_CHAR(S)>
|
||||||
|
inline std::basic_string<Char>
|
||||||
|
vsprintf(const S &format,
|
||||||
|
basic_format_args<typename basic_printf_context_t<
|
||||||
|
internal::basic_buffer<Char>>::type> args) {
|
||||||
|
basic_memory_buffer<Char> buffer;
|
||||||
|
printf(buffer, to_string_view(format), args);
|
||||||
|
return to_string(buffer);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
Formats arguments and returns the result as a string.
|
||||||
|
|
||||||
|
**Example**::
|
||||||
|
|
||||||
|
std::string message = fmt::sprintf("The answer is %d", 42);
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
template <typename S, typename... Args>
|
||||||
|
inline FMT_ENABLE_IF_T(
|
||||||
|
internal::is_string<S>::value, std::basic_string<FMT_CHAR(S)>)
|
||||||
|
sprintf(const S &format, const Args & ... args) {
|
||||||
|
internal::check_format_string<Args...>(format);
|
||||||
|
typedef internal::basic_buffer<FMT_CHAR(S)> buffer;
|
||||||
|
typedef typename basic_printf_context_t<buffer>::type context;
|
||||||
|
format_arg_store<context, Args...> as{ args... };
|
||||||
|
return vsprintf(to_string_view(format),
|
||||||
|
basic_format_args<context>(as));
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename S, typename Char = FMT_CHAR(S)>
|
||||||
|
inline int vfprintf(std::FILE *f, const S &format,
|
||||||
|
basic_format_args<typename basic_printf_context_t<
|
||||||
|
internal::basic_buffer<Char>>::type> args) {
|
||||||
|
basic_memory_buffer<Char> buffer;
|
||||||
|
printf(buffer, to_string_view(format), args);
|
||||||
|
std::size_t size = buffer.size();
|
||||||
|
return std::fwrite(
|
||||||
|
buffer.data(), sizeof(Char), size, f) < size ? -1 : static_cast<int>(size);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
Prints formatted data to the file *f*.
|
||||||
|
|
||||||
|
**Example**::
|
||||||
|
|
||||||
|
fmt::fprintf(stderr, "Don't %s!", "panic");
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
template <typename S, typename... Args>
|
||||||
|
inline FMT_ENABLE_IF_T(internal::is_string<S>::value, int)
|
||||||
|
fprintf(std::FILE *f, const S &format, const Args & ... args) {
|
||||||
|
internal::check_format_string<Args...>(format);
|
||||||
|
typedef internal::basic_buffer<FMT_CHAR(S)> buffer;
|
||||||
|
typedef typename basic_printf_context_t<buffer>::type context;
|
||||||
|
format_arg_store<context, Args...> as{ args... };
|
||||||
|
return vfprintf(f, to_string_view(format),
|
||||||
|
basic_format_args<context>(as));
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename S, typename Char = FMT_CHAR(S)>
|
||||||
|
inline int vprintf(const S &format,
|
||||||
|
basic_format_args<typename basic_printf_context_t<
|
||||||
|
internal::basic_buffer<Char>>::type> args) {
|
||||||
|
return vfprintf(stdout, to_string_view(format), args);
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
Prints formatted data to ``stdout``.
|
||||||
|
|
||||||
|
**Example**::
|
||||||
|
|
||||||
|
fmt::printf("Elapsed time: %.2f seconds", 1.23);
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
template <typename S, typename... Args>
|
||||||
|
inline FMT_ENABLE_IF_T(internal::is_string<S>::value, int)
|
||||||
|
printf(const S &format_str, const Args & ... args) {
|
||||||
|
internal::check_format_string<Args...>(format_str);
|
||||||
|
typedef internal::basic_buffer<FMT_CHAR(S)> buffer;
|
||||||
|
typedef typename basic_printf_context_t<buffer>::type context;
|
||||||
|
format_arg_store<context, Args...> as{ args... };
|
||||||
|
return vprintf(to_string_view(format_str),
|
||||||
|
basic_format_args<context>(as));
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename S, typename Char = FMT_CHAR(S)>
|
||||||
|
inline int vfprintf(std::basic_ostream<Char> &os,
|
||||||
|
const S &format,
|
||||||
|
basic_format_args<typename basic_printf_context_t<
|
||||||
|
internal::basic_buffer<Char>>::type> args) {
|
||||||
|
basic_memory_buffer<Char> buffer;
|
||||||
|
printf(buffer, to_string_view(format), args);
|
||||||
|
internal::write(os, buffer);
|
||||||
|
return static_cast<int>(buffer.size());
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
\rst
|
||||||
|
Prints formatted data to the stream *os*.
|
||||||
|
|
||||||
|
**Example**::
|
||||||
|
|
||||||
|
fmt::fprintf(cerr, "Don't %s!", "panic");
|
||||||
|
\endrst
|
||||||
|
*/
|
||||||
|
template <typename S, typename... Args>
|
||||||
|
inline FMT_ENABLE_IF_T(internal::is_string<S>::value, int)
|
||||||
|
fprintf(std::basic_ostream<FMT_CHAR(S)> &os,
|
||||||
|
const S &format_str, const Args & ... args) {
|
||||||
|
internal::check_format_string<Args...>(format_str);
|
||||||
|
typedef internal::basic_buffer<FMT_CHAR(S)> buffer;
|
||||||
|
typedef typename basic_printf_context_t<buffer>::type context;
|
||||||
|
format_arg_store<context, Args...> as{ args... };
|
||||||
|
return vfprintf(os, to_string_view(format_str),
|
||||||
|
basic_format_args<context>(as));
|
||||||
|
}
|
||||||
|
FMT_END_NAMESPACE
|
||||||
|
|
||||||
|
#endif // FMT_PRINTF_H_
|
308
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/ranges.h
vendored
Normal file
308
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/ranges.h
vendored
Normal file
@ -0,0 +1,308 @@
|
|||||||
|
// Formatting library for C++ - the core API
|
||||||
|
//
|
||||||
|
// Copyright (c) 2012 - present, Victor Zverovich
|
||||||
|
// All rights reserved.
|
||||||
|
//
|
||||||
|
// For the license information refer to format.h.
|
||||||
|
//
|
||||||
|
// Copyright (c) 2018 - present, Remotion (Igor Schulz)
|
||||||
|
// All Rights Reserved
|
||||||
|
// {fmt} support for ranges, containers and types tuple interface.
|
||||||
|
|
||||||
|
#ifndef FMT_RANGES_H_
|
||||||
|
#define FMT_RANGES_H_
|
||||||
|
|
||||||
|
#include "format.h"
|
||||||
|
#include <type_traits>
|
||||||
|
|
||||||
|
// output only up to N items from the range.
|
||||||
|
#ifndef FMT_RANGE_OUTPUT_LENGTH_LIMIT
|
||||||
|
# define FMT_RANGE_OUTPUT_LENGTH_LIMIT 256
|
||||||
|
#endif
|
||||||
|
|
||||||
|
FMT_BEGIN_NAMESPACE
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
struct formatting_base {
|
||||||
|
template <typename ParseContext>
|
||||||
|
FMT_CONSTEXPR auto parse(ParseContext &ctx) -> decltype(ctx.begin()) {
|
||||||
|
return ctx.begin();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename Char, typename Enable = void>
|
||||||
|
struct formatting_range : formatting_base<Char> {
|
||||||
|
static FMT_CONSTEXPR_DECL const std::size_t range_length_limit =
|
||||||
|
FMT_RANGE_OUTPUT_LENGTH_LIMIT; // output only up to N items from the range.
|
||||||
|
Char prefix;
|
||||||
|
Char delimiter;
|
||||||
|
Char postfix;
|
||||||
|
formatting_range() : prefix('{'), delimiter(','), postfix('}') {}
|
||||||
|
static FMT_CONSTEXPR_DECL const bool add_delimiter_spaces = true;
|
||||||
|
static FMT_CONSTEXPR_DECL const bool add_prepostfix_space = false;
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename Char, typename Enable = void>
|
||||||
|
struct formatting_tuple : formatting_base<Char> {
|
||||||
|
Char prefix;
|
||||||
|
Char delimiter;
|
||||||
|
Char postfix;
|
||||||
|
formatting_tuple() : prefix('('), delimiter(','), postfix(')') {}
|
||||||
|
static FMT_CONSTEXPR_DECL const bool add_delimiter_spaces = true;
|
||||||
|
static FMT_CONSTEXPR_DECL const bool add_prepostfix_space = false;
|
||||||
|
};
|
||||||
|
|
||||||
|
namespace internal {
|
||||||
|
|
||||||
|
template <typename RangeT, typename OutputIterator>
|
||||||
|
void copy(const RangeT &range, OutputIterator out) {
|
||||||
|
for (auto it = range.begin(), end = range.end(); it != end; ++it)
|
||||||
|
*out++ = *it;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename OutputIterator>
|
||||||
|
void copy(const char *str, OutputIterator out) {
|
||||||
|
const char *p_curr = str;
|
||||||
|
while (*p_curr) {
|
||||||
|
*out++ = *p_curr++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename OutputIterator>
|
||||||
|
void copy(char ch, OutputIterator out) {
|
||||||
|
*out++ = ch;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Return true value if T has std::string interface, like std::string_view.
|
||||||
|
template <typename T>
|
||||||
|
class is_like_std_string {
|
||||||
|
template <typename U>
|
||||||
|
static auto check(U *p) ->
|
||||||
|
decltype(p->find('a'), p->length(), p->data(), int());
|
||||||
|
template <typename>
|
||||||
|
static void check(...);
|
||||||
|
|
||||||
|
public:
|
||||||
|
static FMT_CONSTEXPR_DECL const bool value =
|
||||||
|
!std::is_void<decltype(check<T>(FMT_NULL))>::value;
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
struct is_like_std_string<fmt::basic_string_view<Char>> : std::true_type {};
|
||||||
|
|
||||||
|
template <typename... Ts>
|
||||||
|
struct conditional_helper {};
|
||||||
|
|
||||||
|
template <typename T, typename _ = void>
|
||||||
|
struct is_range_ : std::false_type {};
|
||||||
|
|
||||||
|
#if !FMT_MSC_VER || FMT_MSC_VER > 1800
|
||||||
|
template <typename T>
|
||||||
|
struct is_range_<T, typename std::conditional<
|
||||||
|
false,
|
||||||
|
conditional_helper<decltype(internal::declval<T>().begin()),
|
||||||
|
decltype(internal::declval<T>().end())>,
|
||||||
|
void>::type> : std::true_type {};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
/// tuple_size and tuple_element check.
|
||||||
|
template <typename T>
|
||||||
|
class is_tuple_like_ {
|
||||||
|
template <typename U>
|
||||||
|
static auto check(U *p) ->
|
||||||
|
decltype(std::tuple_size<U>::value,
|
||||||
|
internal::declval<typename std::tuple_element<0, U>::type>(), int());
|
||||||
|
template <typename>
|
||||||
|
static void check(...);
|
||||||
|
|
||||||
|
public:
|
||||||
|
static FMT_CONSTEXPR_DECL const bool value =
|
||||||
|
!std::is_void<decltype(check<T>(FMT_NULL))>::value;
|
||||||
|
};
|
||||||
|
|
||||||
|
// Check for integer_sequence
|
||||||
|
#if defined(__cpp_lib_integer_sequence) || FMT_MSC_VER >= 1900
|
||||||
|
template <typename T, T... N>
|
||||||
|
using integer_sequence = std::integer_sequence<T, N...>;
|
||||||
|
template <std::size_t... N>
|
||||||
|
using index_sequence = std::index_sequence<N...>;
|
||||||
|
template <std::size_t N>
|
||||||
|
using make_index_sequence = std::make_index_sequence<N>;
|
||||||
|
#else
|
||||||
|
template <typename T, T... N>
|
||||||
|
struct integer_sequence {
|
||||||
|
typedef T value_type;
|
||||||
|
|
||||||
|
static FMT_CONSTEXPR std::size_t size() {
|
||||||
|
return sizeof...(N);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <std::size_t... N>
|
||||||
|
using index_sequence = integer_sequence<std::size_t, N...>;
|
||||||
|
|
||||||
|
template <typename T, std::size_t N, T... Ns>
|
||||||
|
struct make_integer_sequence : make_integer_sequence<T, N - 1, N - 1, Ns...> {};
|
||||||
|
template <typename T, T... Ns>
|
||||||
|
struct make_integer_sequence<T, 0, Ns...> : integer_sequence<T, Ns...> {};
|
||||||
|
|
||||||
|
template <std::size_t N>
|
||||||
|
using make_index_sequence = make_integer_sequence<std::size_t, N>;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
template <class Tuple, class F, size_t... Is>
|
||||||
|
void for_each(index_sequence<Is...>, Tuple &&tup, F &&f) FMT_NOEXCEPT {
|
||||||
|
using std::get;
|
||||||
|
// using free function get<I>(T) now.
|
||||||
|
const int _[] = {0, ((void)f(get<Is>(tup)), 0)...};
|
||||||
|
(void)_; // blocks warnings
|
||||||
|
}
|
||||||
|
|
||||||
|
template <class T>
|
||||||
|
FMT_CONSTEXPR make_index_sequence<std::tuple_size<T>::value>
|
||||||
|
get_indexes(T const &) { return {}; }
|
||||||
|
|
||||||
|
template <class Tuple, class F>
|
||||||
|
void for_each(Tuple &&tup, F &&f) {
|
||||||
|
const auto indexes = get_indexes(tup);
|
||||||
|
for_each(indexes, std::forward<Tuple>(tup), std::forward<F>(f));
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Arg>
|
||||||
|
FMT_CONSTEXPR const char* format_str_quoted(bool add_space, const Arg&,
|
||||||
|
typename std::enable_if<
|
||||||
|
!is_like_std_string<typename std::decay<Arg>::type>::value>::type* = nullptr) {
|
||||||
|
return add_space ? " {}" : "{}";
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Arg>
|
||||||
|
FMT_CONSTEXPR const char* format_str_quoted(bool add_space, const Arg&,
|
||||||
|
typename std::enable_if<
|
||||||
|
is_like_std_string<typename std::decay<Arg>::type>::value>::type* = nullptr) {
|
||||||
|
return add_space ? " \"{}\"" : "\"{}\"";
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR const char* format_str_quoted(bool add_space, const char*) {
|
||||||
|
return add_space ? " \"{}\"" : "\"{}\"";
|
||||||
|
}
|
||||||
|
FMT_CONSTEXPR const wchar_t* format_str_quoted(bool add_space, const wchar_t*) {
|
||||||
|
return add_space ? L" \"{}\"" : L"\"{}\"";
|
||||||
|
}
|
||||||
|
|
||||||
|
FMT_CONSTEXPR const char* format_str_quoted(bool add_space, const char) {
|
||||||
|
return add_space ? " '{}'" : "'{}'";
|
||||||
|
}
|
||||||
|
FMT_CONSTEXPR const wchar_t* format_str_quoted(bool add_space, const wchar_t) {
|
||||||
|
return add_space ? L" '{}'" : L"'{}'";
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace internal
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
struct is_tuple_like {
|
||||||
|
static FMT_CONSTEXPR_DECL const bool value =
|
||||||
|
internal::is_tuple_like_<T>::value && !internal::is_range_<T>::value;
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename TupleT, typename Char>
|
||||||
|
struct formatter<TupleT, Char,
|
||||||
|
typename std::enable_if<fmt::is_tuple_like<TupleT>::value>::type> {
|
||||||
|
private:
|
||||||
|
// C++11 generic lambda for format()
|
||||||
|
template <typename FormatContext>
|
||||||
|
struct format_each {
|
||||||
|
template <typename T>
|
||||||
|
void operator()(const T& v) {
|
||||||
|
if (i > 0) {
|
||||||
|
if (formatting.add_prepostfix_space) {
|
||||||
|
*out++ = ' ';
|
||||||
|
}
|
||||||
|
internal::copy(formatting.delimiter, out);
|
||||||
|
}
|
||||||
|
format_to(out,
|
||||||
|
internal::format_str_quoted(
|
||||||
|
(formatting.add_delimiter_spaces && i > 0), v),
|
||||||
|
v);
|
||||||
|
++i;
|
||||||
|
}
|
||||||
|
|
||||||
|
formatting_tuple<Char>& formatting;
|
||||||
|
std::size_t& i;
|
||||||
|
typename std::add_lvalue_reference<decltype(std::declval<FormatContext>().out())>::type out;
|
||||||
|
};
|
||||||
|
|
||||||
|
public:
|
||||||
|
formatting_tuple<Char> formatting;
|
||||||
|
|
||||||
|
template <typename ParseContext>
|
||||||
|
FMT_CONSTEXPR auto parse(ParseContext &ctx) -> decltype(ctx.begin()) {
|
||||||
|
return formatting.parse(ctx);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename FormatContext = format_context>
|
||||||
|
auto format(const TupleT &values, FormatContext &ctx) -> decltype(ctx.out()) {
|
||||||
|
auto out = ctx.out();
|
||||||
|
std::size_t i = 0;
|
||||||
|
internal::copy(formatting.prefix, out);
|
||||||
|
|
||||||
|
internal::for_each(values, format_each<FormatContext>{formatting, i, out});
|
||||||
|
if (formatting.add_prepostfix_space) {
|
||||||
|
*out++ = ' ';
|
||||||
|
}
|
||||||
|
internal::copy(formatting.postfix, out);
|
||||||
|
|
||||||
|
return ctx.out();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename T>
|
||||||
|
struct is_range {
|
||||||
|
static FMT_CONSTEXPR_DECL const bool value =
|
||||||
|
internal::is_range_<T>::value && !internal::is_like_std_string<T>::value;
|
||||||
|
};
|
||||||
|
|
||||||
|
template <typename RangeT, typename Char>
|
||||||
|
struct formatter<RangeT, Char,
|
||||||
|
typename std::enable_if<fmt::is_range<RangeT>::value>::type> {
|
||||||
|
|
||||||
|
formatting_range<Char> formatting;
|
||||||
|
|
||||||
|
template <typename ParseContext>
|
||||||
|
FMT_CONSTEXPR auto parse(ParseContext &ctx) -> decltype(ctx.begin()) {
|
||||||
|
return formatting.parse(ctx);
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename FormatContext>
|
||||||
|
typename FormatContext::iterator format(
|
||||||
|
const RangeT &values, FormatContext &ctx) {
|
||||||
|
auto out = ctx.out();
|
||||||
|
internal::copy(formatting.prefix, out);
|
||||||
|
std::size_t i = 0;
|
||||||
|
for (auto it = values.begin(), end = values.end(); it != end; ++it) {
|
||||||
|
if (i > 0) {
|
||||||
|
if (formatting.add_prepostfix_space) {
|
||||||
|
*out++ = ' ';
|
||||||
|
}
|
||||||
|
internal::copy(formatting.delimiter, out);
|
||||||
|
}
|
||||||
|
format_to(out,
|
||||||
|
internal::format_str_quoted(
|
||||||
|
(formatting.add_delimiter_spaces && i > 0), *it),
|
||||||
|
*it);
|
||||||
|
if (++i > formatting.range_length_limit) {
|
||||||
|
format_to(out, " ... <other elements>");
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
if (formatting.add_prepostfix_space) {
|
||||||
|
*out++ = ' ';
|
||||||
|
}
|
||||||
|
internal::copy(formatting.postfix, out);
|
||||||
|
return ctx.out();
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
FMT_END_NAMESPACE
|
||||||
|
|
||||||
|
#endif // FMT_RANGES_H_
|
||||||
|
|
160
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/time.h
vendored
Normal file
160
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/bundled/time.h
vendored
Normal file
@ -0,0 +1,160 @@
|
|||||||
|
// Formatting library for C++ - time formatting
|
||||||
|
//
|
||||||
|
// Copyright (c) 2012 - present, Victor Zverovich
|
||||||
|
// All rights reserved.
|
||||||
|
//
|
||||||
|
// For the license information refer to format.h.
|
||||||
|
|
||||||
|
#ifndef FMT_TIME_H_
|
||||||
|
#define FMT_TIME_H_
|
||||||
|
|
||||||
|
#include "format.h"
|
||||||
|
#include <ctime>
|
||||||
|
#include <locale>
|
||||||
|
|
||||||
|
FMT_BEGIN_NAMESPACE
|
||||||
|
|
||||||
|
// Prevents expansion of a preceding token as a function-style macro.
|
||||||
|
// Usage: f FMT_NOMACRO()
|
||||||
|
#define FMT_NOMACRO
|
||||||
|
|
||||||
|
namespace internal{
|
||||||
|
inline null<> localtime_r FMT_NOMACRO(...) { return null<>(); }
|
||||||
|
inline null<> localtime_s(...) { return null<>(); }
|
||||||
|
inline null<> gmtime_r(...) { return null<>(); }
|
||||||
|
inline null<> gmtime_s(...) { return null<>(); }
|
||||||
|
} // namespace internal
|
||||||
|
|
||||||
|
// Thread-safe replacement for std::localtime
|
||||||
|
inline std::tm localtime(std::time_t time) {
|
||||||
|
struct dispatcher {
|
||||||
|
std::time_t time_;
|
||||||
|
std::tm tm_;
|
||||||
|
|
||||||
|
dispatcher(std::time_t t): time_(t) {}
|
||||||
|
|
||||||
|
bool run() {
|
||||||
|
using namespace fmt::internal;
|
||||||
|
return handle(localtime_r(&time_, &tm_));
|
||||||
|
}
|
||||||
|
|
||||||
|
bool handle(std::tm *tm) { return tm != FMT_NULL; }
|
||||||
|
|
||||||
|
bool handle(internal::null<>) {
|
||||||
|
using namespace fmt::internal;
|
||||||
|
return fallback(localtime_s(&tm_, &time_));
|
||||||
|
}
|
||||||
|
|
||||||
|
bool fallback(int res) { return res == 0; }
|
||||||
|
|
||||||
|
#if !FMT_MSC_VER
|
||||||
|
bool fallback(internal::null<>) {
|
||||||
|
using namespace fmt::internal;
|
||||||
|
std::tm *tm = std::localtime(&time_);
|
||||||
|
if (tm) tm_ = *tm;
|
||||||
|
return tm != FMT_NULL;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
dispatcher lt(time);
|
||||||
|
// Too big time values may be unsupported.
|
||||||
|
if (!lt.run())
|
||||||
|
FMT_THROW(format_error("time_t value out of range"));
|
||||||
|
return lt.tm_;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Thread-safe replacement for std::gmtime
|
||||||
|
inline std::tm gmtime(std::time_t time) {
|
||||||
|
struct dispatcher {
|
||||||
|
std::time_t time_;
|
||||||
|
std::tm tm_;
|
||||||
|
|
||||||
|
dispatcher(std::time_t t): time_(t) {}
|
||||||
|
|
||||||
|
bool run() {
|
||||||
|
using namespace fmt::internal;
|
||||||
|
return handle(gmtime_r(&time_, &tm_));
|
||||||
|
}
|
||||||
|
|
||||||
|
bool handle(std::tm *tm) { return tm != FMT_NULL; }
|
||||||
|
|
||||||
|
bool handle(internal::null<>) {
|
||||||
|
using namespace fmt::internal;
|
||||||
|
return fallback(gmtime_s(&tm_, &time_));
|
||||||
|
}
|
||||||
|
|
||||||
|
bool fallback(int res) { return res == 0; }
|
||||||
|
|
||||||
|
#if !FMT_MSC_VER
|
||||||
|
bool fallback(internal::null<>) {
|
||||||
|
std::tm *tm = std::gmtime(&time_);
|
||||||
|
if (tm) tm_ = *tm;
|
||||||
|
return tm != FMT_NULL;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
dispatcher gt(time);
|
||||||
|
// Too big time values may be unsupported.
|
||||||
|
if (!gt.run())
|
||||||
|
FMT_THROW(format_error("time_t value out of range"));
|
||||||
|
return gt.tm_;
|
||||||
|
}
|
||||||
|
|
||||||
|
namespace internal {
|
||||||
|
inline std::size_t strftime(char *str, std::size_t count, const char *format,
|
||||||
|
const std::tm *time) {
|
||||||
|
return std::strftime(str, count, format, time);
|
||||||
|
}
|
||||||
|
|
||||||
|
inline std::size_t strftime(wchar_t *str, std::size_t count,
|
||||||
|
const wchar_t *format, const std::tm *time) {
|
||||||
|
return std::wcsftime(str, count, format, time);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename Char>
|
||||||
|
struct formatter<std::tm, Char> {
|
||||||
|
template <typename ParseContext>
|
||||||
|
auto parse(ParseContext &ctx) -> decltype(ctx.begin()) {
|
||||||
|
auto it = ctx.begin();
|
||||||
|
if (it != ctx.end() && *it == ':')
|
||||||
|
++it;
|
||||||
|
auto end = it;
|
||||||
|
while (end != ctx.end() && *end != '}')
|
||||||
|
++end;
|
||||||
|
tm_format.reserve(internal::to_unsigned(end - it + 1));
|
||||||
|
tm_format.append(it, end);
|
||||||
|
tm_format.push_back('\0');
|
||||||
|
return end;
|
||||||
|
}
|
||||||
|
|
||||||
|
template <typename FormatContext>
|
||||||
|
auto format(const std::tm &tm, FormatContext &ctx) -> decltype(ctx.out()) {
|
||||||
|
basic_memory_buffer<Char> buf;
|
||||||
|
std::size_t start = buf.size();
|
||||||
|
for (;;) {
|
||||||
|
std::size_t size = buf.capacity() - start;
|
||||||
|
std::size_t count =
|
||||||
|
internal::strftime(&buf[start], size, &tm_format[0], &tm);
|
||||||
|
if (count != 0) {
|
||||||
|
buf.resize(start + count);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
if (size >= tm_format.size() * 256) {
|
||||||
|
// If the buffer is 256 times larger than the format string, assume
|
||||||
|
// that `strftime` gives an empty result. There doesn't seem to be a
|
||||||
|
// better way to distinguish the two cases:
|
||||||
|
// https://github.com/fmtlib/fmt/issues/367
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
const std::size_t MIN_GROWTH = 10;
|
||||||
|
buf.reserve(buf.capacity() + (size > MIN_GROWTH ? size : MIN_GROWTH));
|
||||||
|
}
|
||||||
|
return std::copy(buf.begin(), buf.end(), ctx.out());
|
||||||
|
}
|
||||||
|
|
||||||
|
basic_memory_buffer<Char> tm_format;
|
||||||
|
};
|
||||||
|
FMT_END_NAMESPACE
|
||||||
|
|
||||||
|
#endif // FMT_TIME_H_
|
25
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/fmt.h
vendored
Normal file
25
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/fmt.h
vendored
Normal file
@ -0,0 +1,25 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2016-2018 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
//
|
||||||
|
// Include a bundled header-only copy of fmtlib or an external one.
|
||||||
|
// By default spdlog include its own copy.
|
||||||
|
//
|
||||||
|
|
||||||
|
#if !defined(SPDLOG_FMT_EXTERNAL)
|
||||||
|
#ifndef FMT_HEADER_ONLY
|
||||||
|
#define FMT_HEADER_ONLY
|
||||||
|
#endif
|
||||||
|
#ifndef FMT_USE_WINDOWS_H
|
||||||
|
#define FMT_USE_WINDOWS_H 0
|
||||||
|
#endif
|
||||||
|
#include "bundled/core.h"
|
||||||
|
#include "bundled/format.h"
|
||||||
|
#else // external fmtlib
|
||||||
|
#include <fmt/core.h>
|
||||||
|
#include <fmt/format.h>
|
||||||
|
#endif
|
18
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/ostr.h
vendored
Normal file
18
lidar_driver/include/Livox/third_party/spdlog/spdlog/fmt/ostr.h
vendored
Normal file
@ -0,0 +1,18 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2016 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
//
|
||||||
|
// include bundled or external copy of fmtlib's ostream support
|
||||||
|
//
|
||||||
|
#if !defined(SPDLOG_FMT_EXTERNAL)
|
||||||
|
#ifndef FMT_HEADER_ONLY
|
||||||
|
#define FMT_HEADER_ONLY
|
||||||
|
#endif
|
||||||
|
#include "bundled/ostream.h"
|
||||||
|
#include "fmt.h"
|
||||||
|
#else
|
||||||
|
#include <fmt/ostream.h>
|
||||||
|
#endif
|
20
lidar_driver/include/Livox/third_party/spdlog/spdlog/formatter.h
vendored
Normal file
20
lidar_driver/include/Livox/third_party/spdlog/spdlog/formatter.h
vendored
Normal file
@ -0,0 +1,20 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "fmt/fmt.h"
|
||||||
|
#include "spdlog/details/log_msg.h"
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
|
||||||
|
class formatter
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
virtual ~formatter() = default;
|
||||||
|
virtual void format(const details::log_msg &msg, fmt::memory_buffer &dest) = 0;
|
||||||
|
virtual std::unique_ptr<formatter> clone() const = 0;
|
||||||
|
};
|
||||||
|
} // namespace spdlog
|
183
lidar_driver/include/Livox/third_party/spdlog/spdlog/logger.h
vendored
Normal file
183
lidar_driver/include/Livox/third_party/spdlog/spdlog/logger.h
vendored
Normal file
@ -0,0 +1,183 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015-2108 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
// Thread safe logger (except for set_pattern(..), set_formatter(..) and
|
||||||
|
// set_error_handler())
|
||||||
|
// Has name, log level, vector of std::shared sink pointers and formatter
|
||||||
|
// Upon each log write the logger:
|
||||||
|
// 1. Checks if its log level is enough to log the message and if yes:
|
||||||
|
// 2. Call the underlying sinks to do the job.
|
||||||
|
// 3. Each sink use its own private copy of a formatter to format the message
|
||||||
|
// and send to its destination.
|
||||||
|
//
|
||||||
|
// The use of private formatter per sink provides the opportunity to cache some
|
||||||
|
// formatted data,
|
||||||
|
// and support customize format per each sink.
|
||||||
|
|
||||||
|
#include "spdlog/common.h"
|
||||||
|
#include "spdlog/formatter.h"
|
||||||
|
#include "spdlog/sinks/sink.h"
|
||||||
|
|
||||||
|
#include <memory>
|
||||||
|
#include <string>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
|
||||||
|
class logger
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
logger(std::string name, sink_ptr single_sink);
|
||||||
|
logger(std::string name, sinks_init_list sinks);
|
||||||
|
|
||||||
|
template<typename It>
|
||||||
|
logger(std::string name, It begin, It end);
|
||||||
|
|
||||||
|
virtual ~logger();
|
||||||
|
|
||||||
|
logger(const logger &) = delete;
|
||||||
|
logger &operator=(const logger &) = delete;
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void log(level::level_enum lvl, const char *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void log(source_loc loc, level::level_enum lvl, const char *fmt, const Args &... args);
|
||||||
|
|
||||||
|
void log(level::level_enum lvl, const char *msg);
|
||||||
|
|
||||||
|
void log(source_loc loc, level::level_enum lvl, const char *msg);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void trace(const char *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void debug(const char *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void info(const char *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void warn(const char *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void error(const char *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void critical(const char *fmt, const Args &... args);
|
||||||
|
|
||||||
|
#ifdef SPDLOG_WCHAR_TO_UTF8_SUPPORT
|
||||||
|
#ifndef _WIN32
|
||||||
|
#error SPDLOG_WCHAR_TO_UTF8_SUPPORT only supported on windows
|
||||||
|
#else
|
||||||
|
template<typename... Args>
|
||||||
|
void log(level::level_enum lvl, const wchar_t *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void log(source_loc source, level::level_enum lvl, const wchar_t *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void trace(const wchar_t *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void debug(const wchar_t *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void info(const wchar_t *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void warn(const wchar_t *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void error(const wchar_t *fmt, const Args &... args);
|
||||||
|
|
||||||
|
template<typename... Args>
|
||||||
|
void critical(const wchar_t *fmt, const Args &... args);
|
||||||
|
#endif // _WIN32
|
||||||
|
#endif // SPDLOG_WCHAR_TO_UTF8_SUPPORT
|
||||||
|
|
||||||
|
template<class T>
|
||||||
|
void log(level::level_enum lvl, const T &);
|
||||||
|
|
||||||
|
// T can be statically converted to string_view
|
||||||
|
template<class T, typename std::enable_if<std::is_convertible<T, spdlog::string_view_t>::value, T>::type * = nullptr>
|
||||||
|
void log(source_loc loc, level::level_enum lvl, const T &);
|
||||||
|
|
||||||
|
// T cannot be statically converted to string_view
|
||||||
|
template<class T, typename std::enable_if<!std::is_convertible<T, spdlog::string_view_t>::value, T>::type * = nullptr>
|
||||||
|
void log(source_loc loc, level::level_enum lvl, const T &);
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
void trace(const T &msg);
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
void debug(const T &msg);
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
void info(const T &msg);
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
void warn(const T &msg);
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
void error(const T &msg);
|
||||||
|
|
||||||
|
template<typename T>
|
||||||
|
void critical(const T &msg);
|
||||||
|
|
||||||
|
bool should_log(level::level_enum msg_level) const;
|
||||||
|
void set_level(level::level_enum log_level);
|
||||||
|
|
||||||
|
static level::level_enum default_level();
|
||||||
|
level::level_enum level() const;
|
||||||
|
const std::string &name() const;
|
||||||
|
|
||||||
|
// set formatting for the sinks in this logger.
|
||||||
|
// each sink will get a seperate instance of the formatter object.
|
||||||
|
void set_formatter(std::unique_ptr<formatter> formatter);
|
||||||
|
void set_pattern(std::string pattern, pattern_time_type time_type = pattern_time_type::local);
|
||||||
|
|
||||||
|
// flush functions
|
||||||
|
void flush();
|
||||||
|
void flush_on(level::level_enum log_level);
|
||||||
|
level::level_enum flush_level() const;
|
||||||
|
|
||||||
|
// sinks
|
||||||
|
const std::vector<sink_ptr> &sinks() const;
|
||||||
|
std::vector<sink_ptr> &sinks();
|
||||||
|
|
||||||
|
// error handler
|
||||||
|
void set_error_handler(log_err_handler err_handler);
|
||||||
|
log_err_handler error_handler() const;
|
||||||
|
|
||||||
|
// create new logger with same sinks and configuration.
|
||||||
|
virtual std::shared_ptr<logger> clone(std::string logger_name);
|
||||||
|
|
||||||
|
protected:
|
||||||
|
virtual void sink_it_(details::log_msg &msg);
|
||||||
|
virtual void flush_();
|
||||||
|
|
||||||
|
bool should_flush_(const details::log_msg &msg);
|
||||||
|
|
||||||
|
// default error handler.
|
||||||
|
// print the error to stderr with the max rate of 1 message/minute.
|
||||||
|
void default_err_handler_(const std::string &msg);
|
||||||
|
|
||||||
|
// increment the message count (only if defined(SPDLOG_ENABLE_MESSAGE_COUNTER))
|
||||||
|
void incr_msg_counter_(details::log_msg &msg);
|
||||||
|
|
||||||
|
const std::string name_;
|
||||||
|
std::vector<sink_ptr> sinks_;
|
||||||
|
spdlog::level_t level_{spdlog::logger::default_level()};
|
||||||
|
spdlog::level_t flush_level_{level::off};
|
||||||
|
log_err_handler err_handler_{[this](const std::string &msg) { this->default_err_handler_(msg); }};
|
||||||
|
std::atomic<time_t> last_err_time_{0};
|
||||||
|
std::atomic<size_t> msg_counter_{1};
|
||||||
|
};
|
||||||
|
} // namespace spdlog
|
||||||
|
|
||||||
|
#include "details/logger_impl.h"
|
121
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/android_sink.h
vendored
Normal file
121
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/android_sink.h
vendored
Normal file
@ -0,0 +1,121 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef SPDLOG_H
|
||||||
|
#include "spdlog/spdlog.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "spdlog/details/fmt_helper.h"
|
||||||
|
#include "spdlog/details/null_mutex.h"
|
||||||
|
#include "spdlog/details/os.h"
|
||||||
|
#include "spdlog/sinks/base_sink.h"
|
||||||
|
|
||||||
|
#include <android/log.h>
|
||||||
|
#include <chrono>
|
||||||
|
#include <mutex>
|
||||||
|
#include <string>
|
||||||
|
#include <thread>
|
||||||
|
|
||||||
|
#if !defined(SPDLOG_ANDROID_RETRIES)
|
||||||
|
#define SPDLOG_ANDROID_RETRIES 2
|
||||||
|
#endif
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Android sink (logging using __android_log_write)
|
||||||
|
*/
|
||||||
|
template<typename Mutex>
|
||||||
|
class android_sink final : public base_sink<Mutex>
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
explicit android_sink(std::string tag = "spdlog", bool use_raw_msg = false)
|
||||||
|
: tag_(std::move(tag))
|
||||||
|
, use_raw_msg_(use_raw_msg)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void sink_it_(const details::log_msg &msg) override
|
||||||
|
{
|
||||||
|
const android_LogPriority priority = convert_to_android_(msg.level);
|
||||||
|
fmt::memory_buffer formatted;
|
||||||
|
if (use_raw_msg_)
|
||||||
|
{
|
||||||
|
details::fmt_helper::append_string_view(msg.payload, formatted);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
sink::formatter_->format(msg, formatted);
|
||||||
|
}
|
||||||
|
formatted.push_back('\0');
|
||||||
|
const char *msg_output = formatted.data();
|
||||||
|
|
||||||
|
// See system/core/liblog/logger_write.c for explanation of return value
|
||||||
|
int ret = __android_log_write(priority, tag_.c_str(), msg_output);
|
||||||
|
int retry_count = 0;
|
||||||
|
while ((ret == -11 /*EAGAIN*/) && (retry_count < SPDLOG_ANDROID_RETRIES))
|
||||||
|
{
|
||||||
|
details::os::sleep_for_millis(5);
|
||||||
|
ret = __android_log_write(priority, tag_.c_str(), msg_output);
|
||||||
|
retry_count++;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (ret < 0)
|
||||||
|
{
|
||||||
|
throw spdlog_ex("__android_log_write() failed", ret);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void flush_() override {}
|
||||||
|
|
||||||
|
private:
|
||||||
|
static android_LogPriority convert_to_android_(spdlog::level::level_enum level)
|
||||||
|
{
|
||||||
|
switch (level)
|
||||||
|
{
|
||||||
|
case spdlog::level::trace:
|
||||||
|
return ANDROID_LOG_VERBOSE;
|
||||||
|
case spdlog::level::debug:
|
||||||
|
return ANDROID_LOG_DEBUG;
|
||||||
|
case spdlog::level::info:
|
||||||
|
return ANDROID_LOG_INFO;
|
||||||
|
case spdlog::level::warn:
|
||||||
|
return ANDROID_LOG_WARN;
|
||||||
|
case spdlog::level::err:
|
||||||
|
return ANDROID_LOG_ERROR;
|
||||||
|
case spdlog::level::critical:
|
||||||
|
return ANDROID_LOG_FATAL;
|
||||||
|
default:
|
||||||
|
return ANDROID_LOG_DEFAULT;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
std::string tag_;
|
||||||
|
bool use_raw_msg_;
|
||||||
|
};
|
||||||
|
|
||||||
|
using android_sink_mt = android_sink<std::mutex>;
|
||||||
|
using android_sink_st = android_sink<details::null_mutex>;
|
||||||
|
} // namespace sinks
|
||||||
|
|
||||||
|
// Create and register android syslog logger
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> android_logger_mt(const std::string &logger_name, const std::string &tag = "spdlog")
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::android_sink_mt>(logger_name, tag);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> android_logger_st(const std::string &logger_name, const std::string &tag = "spdlog")
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::android_sink_st>(logger_name, tag);
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace spdlog
|
166
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/ansicolor_sink.h
vendored
Normal file
166
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/ansicolor_sink.h
vendored
Normal file
@ -0,0 +1,166 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2017 spdlog authors.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef SPDLOG_H
|
||||||
|
#include "spdlog/spdlog.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "spdlog/details/console_globals.h"
|
||||||
|
#include "spdlog/details/null_mutex.h"
|
||||||
|
#include "spdlog/details/os.h"
|
||||||
|
#include "spdlog/sinks/sink.h"
|
||||||
|
|
||||||
|
#include <memory>
|
||||||
|
#include <mutex>
|
||||||
|
#include <string>
|
||||||
|
#include <unordered_map>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
|
||||||
|
/**
|
||||||
|
* This sink prefixes the output with an ANSI escape sequence color code
|
||||||
|
* depending on the severity
|
||||||
|
* of the message.
|
||||||
|
* If no color terminal detected, omit the escape codes.
|
||||||
|
*/
|
||||||
|
template<typename TargetStream, class ConsoleMutex>
|
||||||
|
class ansicolor_sink final : public sink
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
using mutex_t = typename ConsoleMutex::mutex_t;
|
||||||
|
ansicolor_sink()
|
||||||
|
: target_file_(TargetStream::stream())
|
||||||
|
, mutex_(ConsoleMutex::mutex())
|
||||||
|
|
||||||
|
{
|
||||||
|
should_do_colors_ = details::os::in_terminal(target_file_) && details::os::is_color_terminal();
|
||||||
|
colors_[level::trace] = white;
|
||||||
|
colors_[level::debug] = cyan;
|
||||||
|
colors_[level::info] = green;
|
||||||
|
colors_[level::warn] = yellow + bold;
|
||||||
|
colors_[level::err] = red + bold;
|
||||||
|
colors_[level::critical] = bold + on_red;
|
||||||
|
colors_[level::off] = reset;
|
||||||
|
}
|
||||||
|
|
||||||
|
~ansicolor_sink() override = default;
|
||||||
|
|
||||||
|
ansicolor_sink(const ansicolor_sink &other) = delete;
|
||||||
|
ansicolor_sink &operator=(const ansicolor_sink &other) = delete;
|
||||||
|
|
||||||
|
void set_color(level::level_enum color_level, const std::string &color)
|
||||||
|
{
|
||||||
|
std::lock_guard<mutex_t> lock(mutex_);
|
||||||
|
colors_[color_level] = color;
|
||||||
|
}
|
||||||
|
|
||||||
|
/// Formatting codes
|
||||||
|
const std::string reset = "\033[m";
|
||||||
|
const std::string bold = "\033[1m";
|
||||||
|
const std::string dark = "\033[2m";
|
||||||
|
const std::string underline = "\033[4m";
|
||||||
|
const std::string blink = "\033[5m";
|
||||||
|
const std::string reverse = "\033[7m";
|
||||||
|
const std::string concealed = "\033[8m";
|
||||||
|
const std::string clear_line = "\033[K";
|
||||||
|
|
||||||
|
// Foreground colors
|
||||||
|
const std::string black = "\033[30m";
|
||||||
|
const std::string red = "\033[31m";
|
||||||
|
const std::string green = "\033[32m";
|
||||||
|
const std::string yellow = "\033[33m";
|
||||||
|
const std::string blue = "\033[34m";
|
||||||
|
const std::string magenta = "\033[35m";
|
||||||
|
const std::string cyan = "\033[36m";
|
||||||
|
const std::string white = "\033[37m";
|
||||||
|
|
||||||
|
/// Background colors
|
||||||
|
const std::string on_black = "\033[40m";
|
||||||
|
const std::string on_red = "\033[41m";
|
||||||
|
const std::string on_green = "\033[42m";
|
||||||
|
const std::string on_yellow = "\033[43m";
|
||||||
|
const std::string on_blue = "\033[44m";
|
||||||
|
const std::string on_magenta = "\033[45m";
|
||||||
|
const std::string on_cyan = "\033[46m";
|
||||||
|
const std::string on_white = "\033[47m";
|
||||||
|
|
||||||
|
void log(const details::log_msg &msg) override
|
||||||
|
{
|
||||||
|
// Wrap the originally formatted message in color codes.
|
||||||
|
// If color is not supported in the terminal, log as is instead.
|
||||||
|
std::lock_guard<mutex_t> lock(mutex_);
|
||||||
|
|
||||||
|
fmt::memory_buffer formatted;
|
||||||
|
formatter_->format(msg, formatted);
|
||||||
|
if (should_do_colors_ && msg.color_range_end > msg.color_range_start)
|
||||||
|
{
|
||||||
|
// before color range
|
||||||
|
print_range_(formatted, 0, msg.color_range_start);
|
||||||
|
// in color range
|
||||||
|
print_ccode_(colors_[msg.level]);
|
||||||
|
print_range_(formatted, msg.color_range_start, msg.color_range_end);
|
||||||
|
print_ccode_(reset);
|
||||||
|
// after color range
|
||||||
|
print_range_(formatted, msg.color_range_end, formatted.size());
|
||||||
|
}
|
||||||
|
else // no color
|
||||||
|
{
|
||||||
|
print_range_(formatted, 0, formatted.size());
|
||||||
|
}
|
||||||
|
fflush(target_file_);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flush() override
|
||||||
|
{
|
||||||
|
std::lock_guard<mutex_t> lock(mutex_);
|
||||||
|
fflush(target_file_);
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_pattern(const std::string &pattern) final
|
||||||
|
{
|
||||||
|
std::lock_guard<mutex_t> lock(mutex_);
|
||||||
|
formatter_ = std::unique_ptr<spdlog::formatter>(new pattern_formatter(pattern));
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_formatter(std::unique_ptr<spdlog::formatter> sink_formatter) override
|
||||||
|
{
|
||||||
|
std::lock_guard<mutex_t> lock(mutex_);
|
||||||
|
formatter_ = std::move(sink_formatter);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool should_color()
|
||||||
|
{
|
||||||
|
return should_do_colors_;
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
void print_ccode_(const std::string &color_code)
|
||||||
|
{
|
||||||
|
fwrite(color_code.data(), sizeof(char), color_code.size(), target_file_);
|
||||||
|
}
|
||||||
|
void print_range_(const fmt::memory_buffer &formatted, size_t start, size_t end)
|
||||||
|
{
|
||||||
|
fwrite(formatted.data() + start, sizeof(char), end - start, target_file_);
|
||||||
|
}
|
||||||
|
|
||||||
|
FILE *target_file_;
|
||||||
|
mutex_t &mutex_;
|
||||||
|
|
||||||
|
bool should_do_colors_;
|
||||||
|
std::unordered_map<level::level_enum, std::string, level::level_hasher> colors_;
|
||||||
|
};
|
||||||
|
|
||||||
|
using ansicolor_stdout_sink_mt = ansicolor_sink<details::console_stdout, details::console_mutex>;
|
||||||
|
using ansicolor_stdout_sink_st = ansicolor_sink<details::console_stdout, details::console_nullmutex>;
|
||||||
|
|
||||||
|
using ansicolor_stderr_sink_mt = ansicolor_sink<details::console_stderr, details::console_mutex>;
|
||||||
|
using ansicolor_stderr_sink_st = ansicolor_sink<details::console_stderr, details::console_nullmutex>;
|
||||||
|
|
||||||
|
} // namespace sinks
|
||||||
|
|
||||||
|
} // namespace spdlog
|
69
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/base_sink.h
vendored
Normal file
69
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/base_sink.h
vendored
Normal file
@ -0,0 +1,69 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
//
|
||||||
|
// base sink templated over a mutex (either dummy or real)
|
||||||
|
// concrete implementation should override the sink_it_() and flush_() methods.
|
||||||
|
// locking is taken care of in this class - no locking needed by the
|
||||||
|
// implementers..
|
||||||
|
//
|
||||||
|
|
||||||
|
#include "spdlog/common.h"
|
||||||
|
#include "spdlog/details/log_msg.h"
|
||||||
|
#include "spdlog/formatter.h"
|
||||||
|
#include "spdlog/sinks/sink.h"
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
template<typename Mutex>
|
||||||
|
class base_sink : public sink
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
base_sink() = default;
|
||||||
|
base_sink(const base_sink &) = delete;
|
||||||
|
base_sink &operator=(const base_sink &) = delete;
|
||||||
|
|
||||||
|
void log(const details::log_msg &msg) final
|
||||||
|
{
|
||||||
|
std::lock_guard<Mutex> lock(mutex_);
|
||||||
|
sink_it_(msg);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flush() final
|
||||||
|
{
|
||||||
|
std::lock_guard<Mutex> lock(mutex_);
|
||||||
|
flush_();
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_pattern(const std::string &pattern) final
|
||||||
|
{
|
||||||
|
std::lock_guard<Mutex> lock(mutex_);
|
||||||
|
set_pattern_(pattern);
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_formatter(std::unique_ptr<spdlog::formatter> sink_formatter) final
|
||||||
|
{
|
||||||
|
std::lock_guard<Mutex> lock(mutex_);
|
||||||
|
set_formatter_(std::move(sink_formatter));
|
||||||
|
}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
virtual void sink_it_(const details::log_msg &msg) = 0;
|
||||||
|
virtual void flush_() = 0;
|
||||||
|
|
||||||
|
virtual void set_pattern_(const std::string &pattern)
|
||||||
|
{
|
||||||
|
set_formatter_(details::make_unique<spdlog::pattern_formatter>(pattern));
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual void set_formatter_(std::unique_ptr<spdlog::formatter> sink_formatter)
|
||||||
|
{
|
||||||
|
formatter_ = std::move(sink_formatter);
|
||||||
|
}
|
||||||
|
Mutex mutex_;
|
||||||
|
};
|
||||||
|
} // namespace sinks
|
||||||
|
} // namespace spdlog
|
75
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/basic_file_sink.h
vendored
Normal file
75
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/basic_file_sink.h
vendored
Normal file
@ -0,0 +1,75 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015-2018 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef SPDLOG_H
|
||||||
|
#include "spdlog/spdlog.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "spdlog/details/file_helper.h"
|
||||||
|
#include "spdlog/details/null_mutex.h"
|
||||||
|
#include "spdlog/sinks/base_sink.h"
|
||||||
|
|
||||||
|
#include <mutex>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
/*
|
||||||
|
* Trivial file sink with single file as target
|
||||||
|
*/
|
||||||
|
template<typename Mutex>
|
||||||
|
class basic_file_sink final : public base_sink<Mutex>
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
explicit basic_file_sink(const filename_t &filename, bool truncate = false)
|
||||||
|
{
|
||||||
|
file_helper_.open(filename, truncate);
|
||||||
|
}
|
||||||
|
|
||||||
|
const filename_t &filename() const
|
||||||
|
{
|
||||||
|
return file_helper_.filename();
|
||||||
|
}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void sink_it_(const details::log_msg &msg) override
|
||||||
|
{
|
||||||
|
fmt::memory_buffer formatted;
|
||||||
|
sink::formatter_->format(msg, formatted);
|
||||||
|
file_helper_.write(formatted);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flush_() override
|
||||||
|
{
|
||||||
|
file_helper_.flush();
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
details::file_helper file_helper_;
|
||||||
|
};
|
||||||
|
|
||||||
|
using basic_file_sink_mt = basic_file_sink<std::mutex>;
|
||||||
|
using basic_file_sink_st = basic_file_sink<details::null_mutex>;
|
||||||
|
|
||||||
|
} // namespace sinks
|
||||||
|
|
||||||
|
//
|
||||||
|
// factory functions
|
||||||
|
//
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> basic_logger_mt(const std::string &logger_name, const filename_t &filename, bool truncate = false)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::basic_file_sink_mt>(logger_name, filename, truncate);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> basic_logger_st(const std::string &logger_name, const filename_t &filename, bool truncate = false)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::basic_file_sink_st>(logger_name, filename, truncate);
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace spdlog
|
141
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/daily_file_sink.h
vendored
Normal file
141
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/daily_file_sink.h
vendored
Normal file
@ -0,0 +1,141 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef SPDLOG_H
|
||||||
|
#include "spdlog/spdlog.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "spdlog/details/file_helper.h"
|
||||||
|
#include "spdlog/details/null_mutex.h"
|
||||||
|
#include "spdlog/fmt/fmt.h"
|
||||||
|
#include "spdlog/sinks/base_sink.h"
|
||||||
|
|
||||||
|
#include <chrono>
|
||||||
|
#include <cstdio>
|
||||||
|
#include <ctime>
|
||||||
|
#include <mutex>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Generator of daily log file names in format basename.YYYY-MM-DD.ext
|
||||||
|
*/
|
||||||
|
struct daily_filename_calculator
|
||||||
|
{
|
||||||
|
// Create filename for the form basename.YYYY-MM-DD
|
||||||
|
static filename_t calc_filename(const filename_t &filename, const tm &now_tm)
|
||||||
|
{
|
||||||
|
filename_t basename, ext;
|
||||||
|
std::tie(basename, ext) = details::file_helper::split_by_extension(filename);
|
||||||
|
std::conditional<std::is_same<filename_t::value_type, char>::value, fmt::memory_buffer, fmt::wmemory_buffer>::type w;
|
||||||
|
fmt::format_to(
|
||||||
|
w, SPDLOG_FILENAME_T("{}_{:04d}-{:02d}-{:02d}{}"), basename, now_tm.tm_year + 1900, now_tm.tm_mon + 1, now_tm.tm_mday, ext);
|
||||||
|
return fmt::to_string(w);
|
||||||
|
}
|
||||||
|
};
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Rotating file sink based on date. rotates at midnight
|
||||||
|
*/
|
||||||
|
template<typename Mutex, typename FileNameCalc = daily_filename_calculator>
|
||||||
|
class daily_file_sink final : public base_sink<Mutex>
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
// create daily file sink which rotates on given time
|
||||||
|
daily_file_sink(filename_t base_filename, int rotation_hour, int rotation_minute, bool truncate = false)
|
||||||
|
: base_filename_(std::move(base_filename))
|
||||||
|
, rotation_h_(rotation_hour)
|
||||||
|
, rotation_m_(rotation_minute)
|
||||||
|
, truncate_(truncate)
|
||||||
|
{
|
||||||
|
if (rotation_hour < 0 || rotation_hour > 23 || rotation_minute < 0 || rotation_minute > 59)
|
||||||
|
{
|
||||||
|
throw spdlog_ex("daily_file_sink: Invalid rotation time in ctor");
|
||||||
|
}
|
||||||
|
auto now = log_clock::now();
|
||||||
|
file_helper_.open(FileNameCalc::calc_filename(base_filename_, now_tm(now)), truncate_);
|
||||||
|
rotation_tp_ = next_rotation_tp_();
|
||||||
|
}
|
||||||
|
|
||||||
|
const filename_t &filename() const
|
||||||
|
{
|
||||||
|
return file_helper_.filename();
|
||||||
|
}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void sink_it_(const details::log_msg &msg) override
|
||||||
|
{
|
||||||
|
|
||||||
|
if (msg.time >= rotation_tp_)
|
||||||
|
{
|
||||||
|
file_helper_.open(FileNameCalc::calc_filename(base_filename_, now_tm(msg.time)), truncate_);
|
||||||
|
rotation_tp_ = next_rotation_tp_();
|
||||||
|
}
|
||||||
|
fmt::memory_buffer formatted;
|
||||||
|
sink::formatter_->format(msg, formatted);
|
||||||
|
file_helper_.write(formatted);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flush_() override
|
||||||
|
{
|
||||||
|
file_helper_.flush();
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
tm now_tm(log_clock::time_point tp)
|
||||||
|
{
|
||||||
|
time_t tnow = log_clock::to_time_t(tp);
|
||||||
|
return spdlog::details::os::localtime(tnow);
|
||||||
|
}
|
||||||
|
|
||||||
|
log_clock::time_point next_rotation_tp_()
|
||||||
|
{
|
||||||
|
auto now = log_clock::now();
|
||||||
|
tm date = now_tm(now);
|
||||||
|
date.tm_hour = rotation_h_;
|
||||||
|
date.tm_min = rotation_m_;
|
||||||
|
date.tm_sec = 0;
|
||||||
|
auto rotation_time = log_clock::from_time_t(std::mktime(&date));
|
||||||
|
if (rotation_time > now)
|
||||||
|
{
|
||||||
|
return rotation_time;
|
||||||
|
}
|
||||||
|
return {rotation_time + std::chrono::hours(24)};
|
||||||
|
}
|
||||||
|
|
||||||
|
filename_t base_filename_;
|
||||||
|
int rotation_h_;
|
||||||
|
int rotation_m_;
|
||||||
|
log_clock::time_point rotation_tp_;
|
||||||
|
details::file_helper file_helper_;
|
||||||
|
bool truncate_;
|
||||||
|
};
|
||||||
|
|
||||||
|
using daily_file_sink_mt = daily_file_sink<std::mutex>;
|
||||||
|
using daily_file_sink_st = daily_file_sink<details::null_mutex>;
|
||||||
|
|
||||||
|
} // namespace sinks
|
||||||
|
|
||||||
|
//
|
||||||
|
// factory functions
|
||||||
|
//
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> daily_logger_mt(
|
||||||
|
const std::string &logger_name, const filename_t &filename, int hour = 0, int minute = 0, bool truncate = false)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::daily_file_sink_mt>(logger_name, filename, hour, minute, truncate);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> daily_logger_st(
|
||||||
|
const std::string &logger_name, const filename_t &filename, int hour = 0, int minute = 0, bool truncate = false)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::daily_file_sink_st>(logger_name, filename, hour, minute, truncate);
|
||||||
|
}
|
||||||
|
} // namespace spdlog
|
94
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/dist_sink.h
vendored
Normal file
94
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/dist_sink.h
vendored
Normal file
@ -0,0 +1,94 @@
|
|||||||
|
//
|
||||||
|
// Copyright (c) 2015 David Schury, Gabi Melman
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef SPDLOG_H
|
||||||
|
#include "spdlog/spdlog.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "base_sink.h"
|
||||||
|
#include "spdlog/details/log_msg.h"
|
||||||
|
#include "spdlog/details/null_mutex.h"
|
||||||
|
|
||||||
|
#include <algorithm>
|
||||||
|
#include <memory>
|
||||||
|
#include <mutex>
|
||||||
|
#include <vector>
|
||||||
|
|
||||||
|
// Distribution sink (mux). Stores a vector of sinks which get called when log
|
||||||
|
// is called
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
|
||||||
|
template<typename Mutex>
|
||||||
|
class dist_sink : public base_sink<Mutex>
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
dist_sink() = default;
|
||||||
|
dist_sink(const dist_sink &) = delete;
|
||||||
|
dist_sink &operator=(const dist_sink &) = delete;
|
||||||
|
|
||||||
|
void add_sink(std::shared_ptr<sink> sink)
|
||||||
|
{
|
||||||
|
std::lock_guard<Mutex> lock(base_sink<Mutex>::mutex_);
|
||||||
|
sinks_.push_back(sink);
|
||||||
|
}
|
||||||
|
|
||||||
|
void remove_sink(std::shared_ptr<sink> sink)
|
||||||
|
{
|
||||||
|
std::lock_guard<Mutex> lock(base_sink<Mutex>::mutex_);
|
||||||
|
sinks_.erase(std::remove(sinks_.begin(), sinks_.end(), sink), sinks_.end());
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_sinks(std::vector<std::shared_ptr<sink>> sinks)
|
||||||
|
{
|
||||||
|
std::lock_guard<Mutex> lock(base_sink<Mutex>::mutex_);
|
||||||
|
sinks_ = std::move(sinks);
|
||||||
|
}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void sink_it_(const details::log_msg &msg) override
|
||||||
|
{
|
||||||
|
|
||||||
|
for (auto &sink : sinks_)
|
||||||
|
{
|
||||||
|
if (sink->should_log(msg.level))
|
||||||
|
{
|
||||||
|
sink->log(msg);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void flush_() override
|
||||||
|
{
|
||||||
|
for (auto &sink : sinks_)
|
||||||
|
{
|
||||||
|
sink->flush();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_pattern_(const std::string &pattern) override
|
||||||
|
{
|
||||||
|
set_formatter_(details::make_unique<spdlog::pattern_formatter>(pattern));
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_formatter_(std::unique_ptr<spdlog::formatter> sink_formatter) override
|
||||||
|
{
|
||||||
|
base_sink<Mutex>::formatter_ = std::move(sink_formatter);
|
||||||
|
for (auto &sink : sinks_)
|
||||||
|
{
|
||||||
|
sink->set_formatter(base_sink<Mutex>::formatter_->clone());
|
||||||
|
}
|
||||||
|
}
|
||||||
|
std::vector<std::shared_ptr<sink>> sinks_;
|
||||||
|
};
|
||||||
|
|
||||||
|
using dist_sink_mt = dist_sink<std::mutex>;
|
||||||
|
using dist_sink_st = dist_sink<details::null_mutex>;
|
||||||
|
|
||||||
|
} // namespace sinks
|
||||||
|
} // namespace spdlog
|
54
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/msvc_sink.h
vendored
Normal file
54
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/msvc_sink.h
vendored
Normal file
@ -0,0 +1,54 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2016 Alexander Dalshov.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef SPDLOG_H
|
||||||
|
#include "spdlog/spdlog.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(_WIN32)
|
||||||
|
|
||||||
|
#include "spdlog/details/null_mutex.h"
|
||||||
|
#include "spdlog/sinks/base_sink.h"
|
||||||
|
|
||||||
|
#include <winbase.h>
|
||||||
|
|
||||||
|
#include <mutex>
|
||||||
|
#include <string>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
/*
|
||||||
|
* MSVC sink (logging using OutputDebugStringA)
|
||||||
|
*/
|
||||||
|
template<typename Mutex>
|
||||||
|
class msvc_sink : public base_sink<Mutex>
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
explicit msvc_sink() {}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void sink_it_(const details::log_msg &msg) override
|
||||||
|
{
|
||||||
|
|
||||||
|
fmt::memory_buffer formatted;
|
||||||
|
sink::formatter_->format(msg, formatted);
|
||||||
|
OutputDebugStringA(fmt::to_string(formatted).c_str());
|
||||||
|
}
|
||||||
|
|
||||||
|
void flush_() override {}
|
||||||
|
};
|
||||||
|
|
||||||
|
using msvc_sink_mt = msvc_sink<std::mutex>;
|
||||||
|
using msvc_sink_st = msvc_sink<details::null_mutex>;
|
||||||
|
|
||||||
|
using windebug_sink_mt = msvc_sink_mt;
|
||||||
|
using windebug_sink_st = msvc_sink_st;
|
||||||
|
|
||||||
|
} // namespace sinks
|
||||||
|
} // namespace spdlog
|
||||||
|
|
||||||
|
#endif
|
49
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/null_sink.h
vendored
Normal file
49
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/null_sink.h
vendored
Normal file
@ -0,0 +1,49 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef SPDLOG_H
|
||||||
|
#include "spdlog/spdlog.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "spdlog/details/null_mutex.h"
|
||||||
|
#include "spdlog/sinks/base_sink.h"
|
||||||
|
|
||||||
|
#include <mutex>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
|
||||||
|
template<typename Mutex>
|
||||||
|
class null_sink : public base_sink<Mutex>
|
||||||
|
{
|
||||||
|
protected:
|
||||||
|
void sink_it_(const details::log_msg &) override {}
|
||||||
|
void flush_() override {}
|
||||||
|
};
|
||||||
|
|
||||||
|
using null_sink_mt = null_sink<std::mutex>;
|
||||||
|
using null_sink_st = null_sink<details::null_mutex>;
|
||||||
|
|
||||||
|
} // namespace sinks
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> null_logger_mt(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
auto null_logger = Factory::template create<sinks::null_sink_mt>(logger_name);
|
||||||
|
null_logger->set_level(level::off);
|
||||||
|
return null_logger;
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> null_logger_st(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
auto null_logger = Factory::template create<sinks::null_sink_st>(logger_name);
|
||||||
|
null_logger->set_level(level::off);
|
||||||
|
return null_logger;
|
||||||
|
}
|
||||||
|
|
||||||
|
} // namespace spdlog
|
57
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/ostream_sink.h
vendored
Normal file
57
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/ostream_sink.h
vendored
Normal file
@ -0,0 +1,57 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef SPDLOG_H
|
||||||
|
#include "spdlog/spdlog.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "spdlog/details/null_mutex.h"
|
||||||
|
#include "spdlog/sinks/base_sink.h"
|
||||||
|
|
||||||
|
#include <mutex>
|
||||||
|
#include <ostream>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
template<typename Mutex>
|
||||||
|
class ostream_sink final : public base_sink<Mutex>
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
explicit ostream_sink(std::ostream &os, bool force_flush = false)
|
||||||
|
: ostream_(os)
|
||||||
|
, force_flush_(force_flush)
|
||||||
|
{
|
||||||
|
}
|
||||||
|
ostream_sink(const ostream_sink &) = delete;
|
||||||
|
ostream_sink &operator=(const ostream_sink &) = delete;
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void sink_it_(const details::log_msg &msg) override
|
||||||
|
{
|
||||||
|
fmt::memory_buffer formatted;
|
||||||
|
sink::formatter_->format(msg, formatted);
|
||||||
|
ostream_.write(formatted.data(), static_cast<std::streamsize>(formatted.size()));
|
||||||
|
if (force_flush_)
|
||||||
|
{
|
||||||
|
ostream_.flush();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void flush_() override
|
||||||
|
{
|
||||||
|
ostream_.flush();
|
||||||
|
}
|
||||||
|
|
||||||
|
std::ostream &ostream_;
|
||||||
|
bool force_flush_;
|
||||||
|
};
|
||||||
|
|
||||||
|
using ostream_sink_mt = ostream_sink<std::mutex>;
|
||||||
|
using ostream_sink_st = ostream_sink<details::null_mutex>;
|
||||||
|
|
||||||
|
} // namespace sinks
|
||||||
|
} // namespace spdlog
|
164
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/rotating_file_sink.h
vendored
Normal file
164
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/rotating_file_sink.h
vendored
Normal file
@ -0,0 +1,164 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef SPDLOG_H
|
||||||
|
#include "spdlog/spdlog.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "spdlog/details/file_helper.h"
|
||||||
|
#include "spdlog/details/null_mutex.h"
|
||||||
|
#include "spdlog/fmt/fmt.h"
|
||||||
|
#include "spdlog/sinks/base_sink.h"
|
||||||
|
|
||||||
|
#include <cerrno>
|
||||||
|
#include <chrono>
|
||||||
|
#include <ctime>
|
||||||
|
#include <mutex>
|
||||||
|
#include <string>
|
||||||
|
#include <tuple>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
|
||||||
|
//
|
||||||
|
// Rotating file sink based on size
|
||||||
|
//
|
||||||
|
template<typename Mutex>
|
||||||
|
class rotating_file_sink final : public base_sink<Mutex>
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
rotating_file_sink(filename_t base_filename, std::size_t max_size, std::size_t max_files, bool rotate_on_open=false)
|
||||||
|
: base_filename_(std::move(base_filename))
|
||||||
|
, max_size_(max_size)
|
||||||
|
, max_files_(max_files)
|
||||||
|
{
|
||||||
|
file_helper_.open(calc_filename(base_filename_, 0));
|
||||||
|
current_size_ = file_helper_.size(); // expensive. called only once
|
||||||
|
if (rotate_on_open && current_size_ > 0)
|
||||||
|
{
|
||||||
|
rotate_();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// calc filename according to index and file extension if exists.
|
||||||
|
// e.g. calc_filename("logs/mylog.txt, 3) => "logs/mylog.3.txt".
|
||||||
|
static filename_t calc_filename(const filename_t &filename, std::size_t index)
|
||||||
|
{
|
||||||
|
typename std::conditional<std::is_same<filename_t::value_type, char>::value, fmt::memory_buffer, fmt::wmemory_buffer>::type w;
|
||||||
|
if (index != 0u)
|
||||||
|
{
|
||||||
|
filename_t basename, ext;
|
||||||
|
std::tie(basename, ext) = details::file_helper::split_by_extension(filename);
|
||||||
|
fmt::format_to(w, SPDLOG_FILENAME_T("{}.{}{}"), basename, index, ext);
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
fmt::format_to(w, SPDLOG_FILENAME_T("{}"), filename);
|
||||||
|
}
|
||||||
|
return fmt::to_string(w);
|
||||||
|
}
|
||||||
|
|
||||||
|
const filename_t &filename() const
|
||||||
|
{
|
||||||
|
return file_helper_.filename();
|
||||||
|
}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
void sink_it_(const details::log_msg &msg) override
|
||||||
|
{
|
||||||
|
fmt::memory_buffer formatted;
|
||||||
|
sink::formatter_->format(msg, formatted);
|
||||||
|
current_size_ += formatted.size();
|
||||||
|
if (current_size_ > max_size_)
|
||||||
|
{
|
||||||
|
rotate_();
|
||||||
|
current_size_ = formatted.size();
|
||||||
|
}
|
||||||
|
file_helper_.write(formatted);
|
||||||
|
}
|
||||||
|
|
||||||
|
void flush_() override
|
||||||
|
{
|
||||||
|
file_helper_.flush();
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
// Rotate files:
|
||||||
|
// log.txt -> log.1.txt
|
||||||
|
// log.1.txt -> log.2.txt
|
||||||
|
// log.2.txt -> log.3.txt
|
||||||
|
// log.3.txt -> delete
|
||||||
|
void rotate_()
|
||||||
|
{
|
||||||
|
using details::os::filename_to_str;
|
||||||
|
file_helper_.close();
|
||||||
|
for (auto i = max_files_; i > 0; --i)
|
||||||
|
{
|
||||||
|
filename_t src = calc_filename(base_filename_, i - 1);
|
||||||
|
if (!details::file_helper::file_exists(src))
|
||||||
|
{
|
||||||
|
continue;
|
||||||
|
}
|
||||||
|
filename_t target = calc_filename(base_filename_, i);
|
||||||
|
|
||||||
|
if (!rename_file(src, target))
|
||||||
|
{
|
||||||
|
// if failed try again after a small delay.
|
||||||
|
// this is a workaround to a windows issue, where very high rotation
|
||||||
|
// rates can cause the rename to fail with permission denied (because of antivirus?).
|
||||||
|
details::os::sleep_for_millis(100);
|
||||||
|
if (!rename_file(src, target))
|
||||||
|
{
|
||||||
|
file_helper_.reopen(true); // truncate the log file anyway to prevent it to grow beyond its limit!
|
||||||
|
current_size_ = 0;
|
||||||
|
throw spdlog_ex(
|
||||||
|
"rotating_file_sink: failed renaming " + filename_to_str(src) + " to " + filename_to_str(target), errno);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
file_helper_.reopen(true);
|
||||||
|
}
|
||||||
|
|
||||||
|
// delete the target if exists, and rename the src file to target
|
||||||
|
// return true on success, false otherwise.
|
||||||
|
bool rename_file(const filename_t &src_filename, const filename_t &target_filename)
|
||||||
|
{
|
||||||
|
// try to delete the target file in case it already exists.
|
||||||
|
(void)details::os::remove(target_filename);
|
||||||
|
return details::os::rename(src_filename, target_filename) == 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
filename_t base_filename_;
|
||||||
|
std::size_t max_size_;
|
||||||
|
std::size_t max_files_;
|
||||||
|
std::size_t current_size_;
|
||||||
|
details::file_helper file_helper_;
|
||||||
|
};
|
||||||
|
|
||||||
|
using rotating_file_sink_mt = rotating_file_sink<std::mutex>;
|
||||||
|
using rotating_file_sink_st = rotating_file_sink<details::null_mutex>;
|
||||||
|
|
||||||
|
} // namespace sinks
|
||||||
|
|
||||||
|
//
|
||||||
|
// factory functions
|
||||||
|
//
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> rotating_logger_mt(
|
||||||
|
const std::string &logger_name, const filename_t &filename, size_t max_file_size, size_t max_files, bool rotate_on_open=false)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::rotating_file_sink_mt>(logger_name, filename, max_file_size, max_files, rotate_on_open);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> rotating_logger_st(
|
||||||
|
const std::string &logger_name, const filename_t &filename, size_t max_file_size, size_t max_files, bool rotate_on_open = false)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::rotating_file_sink_st>(logger_name, filename, max_file_size, max_files, rotate_on_open);
|
||||||
|
}
|
||||||
|
} // namespace spdlog
|
54
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/sink.h
vendored
Normal file
54
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/sink.h
vendored
Normal file
@ -0,0 +1,54 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "spdlog/details/log_msg.h"
|
||||||
|
#include "spdlog/details/pattern_formatter.h"
|
||||||
|
#include "spdlog/formatter.h"
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
class sink
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
sink() = default;
|
||||||
|
|
||||||
|
explicit sink(std::unique_ptr<spdlog::formatter> formatter)
|
||||||
|
: formatter_{std::move(formatter)}
|
||||||
|
{
|
||||||
|
}
|
||||||
|
|
||||||
|
virtual ~sink() = default;
|
||||||
|
virtual void log(const details::log_msg &msg) = 0;
|
||||||
|
virtual void flush() = 0;
|
||||||
|
virtual void set_pattern(const std::string &pattern) = 0;
|
||||||
|
virtual void set_formatter(std::unique_ptr<spdlog::formatter> sink_formatter) = 0;
|
||||||
|
|
||||||
|
bool should_log(level::level_enum msg_level) const
|
||||||
|
{
|
||||||
|
return msg_level >= level_.load(std::memory_order_relaxed);
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_level(level::level_enum log_level)
|
||||||
|
{
|
||||||
|
level_.store(log_level);
|
||||||
|
}
|
||||||
|
|
||||||
|
level::level_enum level() const
|
||||||
|
{
|
||||||
|
return static_cast<spdlog::level::level_enum>(level_.load(std::memory_order_relaxed));
|
||||||
|
}
|
||||||
|
|
||||||
|
protected:
|
||||||
|
// sink log level - default is all
|
||||||
|
level_t level_{level::trace};
|
||||||
|
|
||||||
|
// sink formatter - default is full format
|
||||||
|
std::unique_ptr<spdlog::formatter> formatter_{details::make_unique<spdlog::pattern_formatter>()};
|
||||||
|
};
|
||||||
|
|
||||||
|
} // namespace sinks
|
||||||
|
} // namespace spdlog
|
56
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/stdout_color_sinks.h
vendored
Normal file
56
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/stdout_color_sinks.h
vendored
Normal file
@ -0,0 +1,56 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2018 spdlog
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef SPDLOG_H
|
||||||
|
#include "spdlog/spdlog.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef _WIN32
|
||||||
|
#include "spdlog/sinks/wincolor_sink.h"
|
||||||
|
#else
|
||||||
|
#include "spdlog/sinks/ansicolor_sink.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
namespace sinks {
|
||||||
|
#ifdef _WIN32
|
||||||
|
using stdout_color_sink_mt = wincolor_stdout_sink_mt;
|
||||||
|
using stdout_color_sink_st = wincolor_stdout_sink_st;
|
||||||
|
using stderr_color_sink_mt = wincolor_stderr_sink_mt;
|
||||||
|
using stderr_color_sink_st = wincolor_stderr_sink_st;
|
||||||
|
#else
|
||||||
|
using stdout_color_sink_mt = ansicolor_stdout_sink_mt;
|
||||||
|
using stdout_color_sink_st = ansicolor_stdout_sink_st;
|
||||||
|
using stderr_color_sink_mt = ansicolor_stderr_sink_mt;
|
||||||
|
using stderr_color_sink_st = ansicolor_stderr_sink_st;
|
||||||
|
#endif
|
||||||
|
} // namespace sinks
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> stdout_color_mt(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::stdout_color_sink_mt>(logger_name);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> stdout_color_st(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::stdout_color_sink_st>(logger_name);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> stderr_color_mt(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::stderr_color_sink_mt>(logger_name);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> stderr_color_st(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::stderr_color_sink_st>(logger_name);
|
||||||
|
}
|
||||||
|
} // namespace spdlog
|
102
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/stdout_sinks.h
vendored
Normal file
102
lidar_driver/include/Livox/third_party/spdlog/spdlog/sinks/stdout_sinks.h
vendored
Normal file
@ -0,0 +1,102 @@
|
|||||||
|
//
|
||||||
|
// Copyright(c) 2015 Gabi Melman.
|
||||||
|
// Distributed under the MIT License (http://opensource.org/licenses/MIT)
|
||||||
|
//
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifndef SPDLOG_H
|
||||||
|
#include "spdlog/spdlog.h"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#include "spdlog/details/console_globals.h"
|
||||||
|
#include "spdlog/details/null_mutex.h"
|
||||||
|
|
||||||
|
#include <cstdio>
|
||||||
|
#include <memory>
|
||||||
|
#include <mutex>
|
||||||
|
|
||||||
|
namespace spdlog {
|
||||||
|
|
||||||
|
namespace sinks {
|
||||||
|
|
||||||
|
template<typename TargetStream, typename ConsoleMutex>
|
||||||
|
class stdout_sink final : public sink
|
||||||
|
{
|
||||||
|
public:
|
||||||
|
using mutex_t = typename ConsoleMutex::mutex_t;
|
||||||
|
stdout_sink()
|
||||||
|
: mutex_(ConsoleMutex::mutex())
|
||||||
|
, file_(TargetStream::stream())
|
||||||
|
{
|
||||||
|
}
|
||||||
|
~stdout_sink() override = default;
|
||||||
|
|
||||||
|
stdout_sink(const stdout_sink &other) = delete;
|
||||||
|
stdout_sink &operator=(const stdout_sink &other) = delete;
|
||||||
|
|
||||||
|
void log(const details::log_msg &msg) override
|
||||||
|
{
|
||||||
|
std::lock_guard<mutex_t> lock(mutex_);
|
||||||
|
fmt::memory_buffer formatted;
|
||||||
|
formatter_->format(msg, formatted);
|
||||||
|
fwrite(formatted.data(), sizeof(char), formatted.size(), file_);
|
||||||
|
fflush(TargetStream::stream());
|
||||||
|
}
|
||||||
|
|
||||||
|
void flush() override
|
||||||
|
{
|
||||||
|
std::lock_guard<mutex_t> lock(mutex_);
|
||||||
|
fflush(file_);
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_pattern(const std::string &pattern) override
|
||||||
|
{
|
||||||
|
std::lock_guard<mutex_t> lock(mutex_);
|
||||||
|
formatter_ = std::unique_ptr<spdlog::formatter>(new pattern_formatter(pattern));
|
||||||
|
}
|
||||||
|
|
||||||
|
void set_formatter(std::unique_ptr<spdlog::formatter> sink_formatter) override
|
||||||
|
{
|
||||||
|
std::lock_guard<mutex_t> lock(mutex_);
|
||||||
|
formatter_ = std::move(sink_formatter);
|
||||||
|
}
|
||||||
|
|
||||||
|
private:
|
||||||
|
mutex_t &mutex_;
|
||||||
|
FILE *file_;
|
||||||
|
};
|
||||||
|
|
||||||
|
using stdout_sink_mt = stdout_sink<details::console_stdout, details::console_mutex>;
|
||||||
|
using stdout_sink_st = stdout_sink<details::console_stdout, details::console_nullmutex>;
|
||||||
|
|
||||||
|
using stderr_sink_mt = stdout_sink<details::console_stderr, details::console_mutex>;
|
||||||
|
using stderr_sink_st = stdout_sink<details::console_stderr, details::console_nullmutex>;
|
||||||
|
|
||||||
|
} // namespace sinks
|
||||||
|
|
||||||
|
// factory methods
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> stdout_logger_mt(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::stdout_sink_mt>(logger_name);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> stdout_logger_st(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::stdout_sink_st>(logger_name);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> stderr_logger_mt(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::stderr_sink_mt>(logger_name);
|
||||||
|
}
|
||||||
|
|
||||||
|
template<typename Factory = default_factory>
|
||||||
|
inline std::shared_ptr<logger> stderr_logger_st(const std::string &logger_name)
|
||||||
|
{
|
||||||
|
return Factory::template create<sinks::stderr_sink_st>(logger_name);
|
||||||
|
}
|
||||||
|
} // namespace spdlog
|
Some files were not shown because too many files have changed in this diff Show More
Loading…
Reference in New Issue
Block a user