UPDATE openvino
This commit is contained in:
@ -15,29 +15,24 @@ from Vision.tool.CameraRVC import camera
|
|||||||
from Vision.yolo.yolov8_pt_seg import yolov8_segment
|
from Vision.yolo.yolov8_pt_seg import yolov8_segment
|
||||||
from Vision.yolo.yolov8_openvino import yolov8_segment_openvino
|
from Vision.yolo.yolov8_openvino import yolov8_segment_openvino
|
||||||
from Vision.tool.utils import find_position
|
from Vision.tool.utils import find_position
|
||||||
from Vision.tool.utils import class_names
|
|
||||||
import os
|
import os
|
||||||
|
|
||||||
class Detection:
|
class Detection:
|
||||||
|
|
||||||
def __init__(self, use_openvino_model = False):
|
def __init__(self, use_openvino_model = False):
|
||||||
print(os.getcwd())
|
|
||||||
self.use_openvino_model = use_openvino_model
|
self.use_openvino_model = use_openvino_model
|
||||||
if self.use_openvino_model == False:
|
if self.use_openvino_model==False:
|
||||||
model_path = ''.join([os.getcwd(), '/model/pt/best.pt'])
|
model_path = ''.join([os.getcwd(), '/model/pt/best.pt'])
|
||||||
device = 'cpu'
|
device = 'cpu'
|
||||||
|
self.camera_rvc = camera()
|
||||||
self.model = yolov8_segment()
|
self.model = yolov8_segment()
|
||||||
self.model.load_model(model_path, device)
|
self.model.load_model(model_path, device)
|
||||||
else:
|
else:
|
||||||
model_path = ''.join([os.getcwd(), '/model/openvino/bset.xml'])
|
model_path = ''.join([os.getcwd(), '/model/openvino/last-0903.xml'])
|
||||||
device = 'CPU'
|
device = 'CPU'
|
||||||
|
self.camera_rvc = camera()
|
||||||
self.model = yolov8_segment_openvino(model_path, device, conf_thres=0.3, iou_thres=0.3)
|
self.model = yolov8_segment_openvino(model_path, device, conf_thres=0.3, iou_thres=0.3)
|
||||||
|
|
||||||
img_path = ''.join([os.getcwd(), '/model/data/test0910.png'])
|
|
||||||
point_path = ''.join([os.getcwd(), '/model/data/test0910.xyz'])
|
|
||||||
self.img = cv2.imread(img_path)
|
|
||||||
self.point = np.loadtxt(point_path).reshape((1080, 1440, 3))
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
def get_position(self, Point_isVision=True):
|
def get_position(self, Point_isVision=True):
|
||||||
@ -46,169 +41,172 @@ class Detection:
|
|||||||
:param api: None
|
:param api: None
|
||||||
:return: ret , img, (x,y,z), (nx, ny, nz)
|
:return: ret , img, (x,y,z), (nx, ny, nz)
|
||||||
'''
|
'''
|
||||||
#ret, img, pm = self.camera_rvc.get_img_and_point_map() # 拍照,获取图像及
|
ret, img, pm = self.camera_rvc.get_img_and_point_map() # 拍照,获取图像及
|
||||||
ret = 1
|
if self.camera_rvc.caminit_isok == True:
|
||||||
img = self.img
|
if ret == 1:
|
||||||
pm = self.point
|
if self.use_openvino_model == False:
|
||||||
if ret == 1:
|
flag, det_cpu, dst_img, masks, category_names = self.model.model_inference(img, 0)
|
||||||
if self.use_openvino_model == False:
|
|
||||||
flag, det_cpu, dst_img, masks, category_names = self.model.model_inference(img, 0)
|
|
||||||
else:
|
|
||||||
flag, det_cpu, scores, masks, category_names = self.model.segment_objects(img)
|
|
||||||
dst_img = img
|
|
||||||
if flag == 1:
|
|
||||||
xyz = []
|
|
||||||
nx_ny_nz = []
|
|
||||||
RegionalArea = []
|
|
||||||
Depth_Z = []
|
|
||||||
uv = []
|
|
||||||
seg_point = []
|
|
||||||
if Point_isVision == True:
|
|
||||||
pm2 = pm.copy()
|
|
||||||
pm2 = pm2.reshape(-1, 3)
|
|
||||||
pm2 = pm2[~np.isnan(pm2).all(axis=-1), :]
|
|
||||||
pm2[:, 2] = pm2[:, 2] + 0.25
|
|
||||||
pcd2 = o3d.geometry.PointCloud()
|
|
||||||
pcd2.points = o3d.utility.Vector3dVector(pm2)
|
|
||||||
# o3d.visualization.draw_geometries([pcd2])
|
|
||||||
|
|
||||||
for i, item in enumerate(det_cpu):
|
|
||||||
|
|
||||||
# 画box
|
|
||||||
box_x1, box_y1, box_x2, box_y2 = item[0:4].astype(np.int32)
|
|
||||||
if self.use_openvino_model == False:
|
|
||||||
label = category_names[int(item[5])]
|
|
||||||
else:
|
|
||||||
label = class_names[int(item[4])]
|
|
||||||
rand_color = (0, 255, 255)
|
|
||||||
score = item[4]
|
|
||||||
org = (int((box_x1 + box_x2) / 2), int((box_y1 + box_y2) / 2))
|
|
||||||
x_center = int((box_x1 + box_x2) / 2)
|
|
||||||
y_center = int((box_y1 + box_y2) / 2)
|
|
||||||
text = '{}|{:.2f}'.format(label, score)
|
|
||||||
cv2.putText(img, text, org=org, fontFace=cv2.FONT_HERSHEY_SIMPLEX, fontScale=0.8,
|
|
||||||
color=rand_color,
|
|
||||||
thickness=2)
|
|
||||||
# 画mask
|
|
||||||
# mask = masks[i].cpu().numpy().astype(int)
|
|
||||||
if self.use_openvino_model == False:
|
|
||||||
mask = masks[i].cpu().data.numpy().astype(int)
|
|
||||||
else:
|
|
||||||
mask = masks[i].astype(int)
|
|
||||||
mask = mask[box_y1:box_y2, box_x1:box_x2]
|
|
||||||
|
|
||||||
# mask = masks[i].numpy().astype(int)
|
|
||||||
h, w = box_y2 - box_y1, box_x2 - box_x1
|
|
||||||
mask_colored = np.zeros((h, w, 3), dtype=np.uint8)
|
|
||||||
mask_colored[np.where(mask)] = rand_color
|
|
||||||
##################################
|
|
||||||
imgray = cv2.cvtColor(mask_colored, cv2.COLOR_BGR2GRAY)
|
|
||||||
# cv2.imshow('mask',imgray)
|
|
||||||
# cv2.waitKey(1)
|
|
||||||
# 2、二进制图像
|
|
||||||
ret, binary = cv2.threshold(imgray, 10, 255, 0)
|
|
||||||
# 阈值 二进制图像
|
|
||||||
# cv2.imshow('bin',binary)
|
|
||||||
# cv2.waitKey(1)
|
|
||||||
contours, hierarchy = cv2.findContours(binary, cv2.RETR_TREE, cv2.CHAIN_APPROX_NONE)
|
|
||||||
# all_piont_list = contours_in(contours)
|
|
||||||
# print(len(all_piont_list))
|
|
||||||
max_contour = None
|
|
||||||
max_perimeter = 0
|
|
||||||
for contour in contours: # 排除小分割区域或干扰区域
|
|
||||||
perimeter = cv2.arcLength(contour, True)
|
|
||||||
if perimeter > max_perimeter:
|
|
||||||
max_perimeter = perimeter
|
|
||||||
max_contour = contour
|
|
||||||
'''
|
|
||||||
提取区域范围内的(x, y)
|
|
||||||
'''
|
|
||||||
mask_inside = np.zeros(binary.shape, np.uint8)
|
|
||||||
cv2.drawContours(mask_inside, [max_contour], 0, 255, -1)
|
|
||||||
pixel_point2 = cv2.findNonZero(mask_inside)
|
|
||||||
# result = np.zeros_like(color_image)
|
|
||||||
select_point = []
|
|
||||||
for i in range(pixel_point2.shape[0]):
|
|
||||||
select_point.append(pm[pixel_point2[i][0][1] + box_y1, pixel_point2[i][0][0] + box_x1])
|
|
||||||
select_point = np.array(select_point)
|
|
||||||
pm_seg = select_point.reshape(-1, 3)
|
|
||||||
pm_seg = pm_seg[~np.isnan(pm_seg).all(axis=-1), :] # 剔除 nan
|
|
||||||
# cv2.imshow('result', piont_result)
|
|
||||||
|
|
||||||
'''
|
|
||||||
拟合平面,计算法向量
|
|
||||||
'''
|
|
||||||
pcd = o3d.geometry.PointCloud()
|
|
||||||
pcd.points = o3d.utility.Vector3dVector(pm_seg)
|
|
||||||
plane_model, inliers = pcd.segment_plane(distance_threshold=0.01,
|
|
||||||
ransac_n=5,
|
|
||||||
num_iterations=5000)
|
|
||||||
[a, b, c, d] = plane_model
|
|
||||||
# print(f"Plane equation: {a:.2f}x + {b:.2f}y + {c:.2f}z + {d:.2f} = 0")
|
|
||||||
|
|
||||||
# inlier_cloud = pcd.select_by_index(inliers) # 点云可视化
|
|
||||||
# inlier_cloud.paint_uniform_color([1.0, 0, 0])
|
|
||||||
# outlier_cloud = pcd.select_by_index(inliers, invert=True)
|
|
||||||
# outlier_cloud.paint_uniform_color([0, 1, 0])
|
|
||||||
# o3d.visualization.draw_geometries([inlier_cloud, outlier_cloud])
|
|
||||||
|
|
||||||
'''
|
|
||||||
拟合最小外接矩形,计算矩形中心
|
|
||||||
'''
|
|
||||||
|
|
||||||
rect = cv2.minAreaRect(max_contour)
|
|
||||||
# cv2.boxPoints可以将轮廓点转换为四个角点坐标
|
|
||||||
box = cv2.boxPoints(rect)
|
|
||||||
# 这一步不影响后面的画图,但是可以保证四个角点坐标为顺时针
|
|
||||||
startidx = box.sum(axis=1).argmin()
|
|
||||||
box = np.roll(box, 4 - startidx, 0)
|
|
||||||
# 在原图上画出预测的外接矩形
|
|
||||||
box = box.reshape((-1, 1, 2)).astype(np.int32)
|
|
||||||
box = box + [[[box_x1, box_y1]], [[box_x1, box_y1]], [[box_x1, box_y1]], [[box_x1, box_y1]]]
|
|
||||||
|
|
||||||
x_rotation_center = int((box[0][0][0] + box[1][0][0] + box[2][0][0] + box[3][0][0]) / 4)
|
|
||||||
y_rotation_center = int((box[0][0][1] + box[1][0][1] + box[2][0][1] + box[3][0][1]) / 4)
|
|
||||||
point_x, point_y, point_z = pm[y_rotation_center, x_rotation_center]
|
|
||||||
cv2.circle(img, (x_rotation_center, y_rotation_center), 4, (255, 255, 255), 5) # 标出中心点
|
|
||||||
if np.isnan(point_x): # 点云值为无效值
|
|
||||||
continue
|
|
||||||
else:
|
|
||||||
xyz.append([point_x * 1000, point_y * 1000, point_z * 1000])
|
|
||||||
Depth_Z.append(point_z * 1000)
|
|
||||||
nx_ny_nz.append([a, b, c])
|
|
||||||
RegionalArea.append(cv2.contourArea(max_contour))
|
|
||||||
uv.append([x_rotation_center, y_rotation_center])
|
|
||||||
seg_point.append(pm_seg)
|
|
||||||
cv2.polylines(img, [box], True, (0, 255, 0), 2)
|
|
||||||
|
|
||||||
_idx = find_position(Depth_Z, RegionalArea, 100, True)
|
|
||||||
|
|
||||||
if _idx == None:
|
|
||||||
return 1, img, None, None
|
|
||||||
else:
|
else:
|
||||||
cv2.circle(img, (uv[_idx][0], uv[_idx][1]), 30, (0, 0, 255), 20) # 标出中心点
|
flag, det_cpu, scores, masks, category_names = self.model.segment_objects(img)
|
||||||
|
if flag == 1:
|
||||||
|
xyz = []
|
||||||
|
nx_ny_nz = []
|
||||||
|
RegionalArea = []
|
||||||
|
Depth_Z = []
|
||||||
|
uv = []
|
||||||
|
seg_point = []
|
||||||
|
if Point_isVision==True:
|
||||||
|
pm2 = pm.copy()
|
||||||
|
pm2 = pm2.reshape(-1, 3)
|
||||||
|
pm2 = pm2[~np.isnan(pm2).all(axis=-1), :]
|
||||||
|
pm2[:, 2] = pm2[:, 2] + 0.25
|
||||||
|
pcd2 = o3d.geometry.PointCloud()
|
||||||
|
pcd2.points = o3d.utility.Vector3dVector(pm2)
|
||||||
|
# o3d.visualization.draw_geometries([pcd2])
|
||||||
|
|
||||||
if Point_isVision == True:
|
for i, item in enumerate(det_cpu):
|
||||||
|
|
||||||
|
# 画box
|
||||||
|
box_x1, box_y1, box_x2, box_y2 = item[0:4].astype(np.int32)
|
||||||
|
label = category_names[int(item[5])]
|
||||||
|
rand_color = (0, 255, 255)
|
||||||
|
score = item[4]
|
||||||
|
org = (int((box_x1 + box_x2) / 2), int((box_y1 + box_y2) / 2))
|
||||||
|
x_center = int((box_x1 + box_x2) / 2)
|
||||||
|
y_center = int((box_y1 + box_y2) / 2)
|
||||||
|
text = '{}|{:.2f}'.format(label, score)
|
||||||
|
cv2.putText(img, text, org=org, fontFace=cv2.FONT_HERSHEY_SIMPLEX, fontScale=0.8,
|
||||||
|
color=rand_color,
|
||||||
|
thickness=2)
|
||||||
|
# 画mask
|
||||||
|
# mask = masks[i].cpu().numpy().astype(int)
|
||||||
|
if self.use_openvino_model == False:
|
||||||
|
mask = masks[i].cpu().data.numpy().astype(int)
|
||||||
|
else:
|
||||||
|
mask = masks[i].astype(int)
|
||||||
|
mask = mask[box_y1:box_y2, box_x1:box_x2]
|
||||||
|
|
||||||
|
# mask = masks[i].numpy().astype(int)
|
||||||
|
h, w = box_y2 - box_y1, box_x2 - box_x1
|
||||||
|
mask_colored = np.zeros((h, w, 3), dtype=np.uint8)
|
||||||
|
mask_colored[np.where(mask)] = rand_color
|
||||||
|
##################################
|
||||||
|
imgray = cv2.cvtColor(mask_colored, cv2.COLOR_BGR2GRAY)
|
||||||
|
# cv2.imshow('mask',imgray)
|
||||||
|
# cv2.waitKey(1)
|
||||||
|
# 2、二进制图像
|
||||||
|
ret, binary = cv2.threshold(imgray, 10, 255, 0)
|
||||||
|
# 阈值 二进制图像
|
||||||
|
# cv2.imshow('bin',binary)
|
||||||
|
# cv2.waitKey(1)
|
||||||
|
contours, hierarchy = cv2.findContours(binary, cv2.RETR_TREE, cv2.CHAIN_APPROX_NONE)
|
||||||
|
# all_piont_list = contours_in(contours)
|
||||||
|
# print(len(all_piont_list))
|
||||||
|
max_contour = None
|
||||||
|
max_perimeter = 0
|
||||||
|
for contour in contours: # 排除小分割区域或干扰区域
|
||||||
|
perimeter = cv2.arcLength(contour, True)
|
||||||
|
if perimeter > max_perimeter:
|
||||||
|
max_perimeter = perimeter
|
||||||
|
max_contour = contour
|
||||||
|
'''
|
||||||
|
提取区域范围内的(x, y)
|
||||||
|
'''
|
||||||
|
mask_inside = np.zeros(binary.shape, np.uint8)
|
||||||
|
cv2.drawContours(mask_inside, [max_contour], 0, 255, -1)
|
||||||
|
pixel_point2 = cv2.findNonZero(mask_inside)
|
||||||
|
# result = np.zeros_like(color_image)
|
||||||
|
select_point = []
|
||||||
|
for i in range(pixel_point2.shape[0]):
|
||||||
|
select_point.append(pm[pixel_point2[i][0][1]+box_y1, pixel_point2[i][0][0]+box_x1])
|
||||||
|
select_point = np.array(select_point)
|
||||||
|
pm_seg = select_point.reshape(-1, 3)
|
||||||
|
pm_seg = pm_seg[~np.isnan(pm_seg).all(axis=-1), :] # 剔除 nan
|
||||||
|
if pm_seg.size<300:
|
||||||
|
print("分割点云数量较少,无法拟合平面")
|
||||||
|
continue
|
||||||
|
|
||||||
|
# cv2.imshow('result', piont_result)
|
||||||
|
|
||||||
|
'''
|
||||||
|
拟合平面,计算法向量
|
||||||
|
'''
|
||||||
pcd = o3d.geometry.PointCloud()
|
pcd = o3d.geometry.PointCloud()
|
||||||
pcd.points = o3d.utility.Vector3dVector(seg_point[_idx])
|
pcd.points = o3d.utility.Vector3dVector(pm_seg)
|
||||||
plane_model, inliers = pcd.segment_plane(distance_threshold=0.01,
|
plane_model, inliers = pcd.segment_plane(distance_threshold=0.01,
|
||||||
ransac_n=5,
|
ransac_n=5,
|
||||||
num_iterations=5000)
|
num_iterations=5000)
|
||||||
inlier_cloud = pcd.select_by_index(inliers) # 点云可视化
|
[a, b, c, d] = plane_model
|
||||||
inlier_cloud.paint_uniform_color([1.0, 0, 0])
|
#print(f"Plane equation: {a:.2f}x + {b:.2f}y + {c:.2f}z + {d:.2f} = 0")
|
||||||
outlier_cloud = pcd.select_by_index(inliers, invert=True)
|
|
||||||
outlier_cloud.paint_uniform_color([0, 1, 0])
|
# inlier_cloud = pcd.select_by_index(inliers) # 点云可视化
|
||||||
o3d.visualization.draw_geometries([inlier_cloud, outlier_cloud, pcd2])
|
# inlier_cloud.paint_uniform_color([1.0, 0, 0])
|
||||||
|
# outlier_cloud = pcd.select_by_index(inliers, invert=True)
|
||||||
|
# outlier_cloud.paint_uniform_color([0, 1, 0])
|
||||||
|
# o3d.visualization.draw_geometries([inlier_cloud, outlier_cloud])
|
||||||
|
|
||||||
|
'''
|
||||||
|
拟合最小外接矩形,计算矩形中心
|
||||||
|
'''
|
||||||
|
|
||||||
|
rect = cv2.minAreaRect(max_contour)
|
||||||
|
# cv2.boxPoints可以将轮廓点转换为四个角点坐标
|
||||||
|
box = cv2.boxPoints(rect)
|
||||||
|
# 这一步不影响后面的画图,但是可以保证四个角点坐标为顺时针
|
||||||
|
startidx = box.sum(axis=1).argmin()
|
||||||
|
box = np.roll(box, 4 - startidx, 0)
|
||||||
|
# 在原图上画出预测的外接矩形
|
||||||
|
box = box.reshape((-1, 1, 2)).astype(np.int32)
|
||||||
|
box = box + [[[box_x1, box_y1]], [[box_x1, box_y1]], [[box_x1, box_y1]], [[box_x1, box_y1]]]
|
||||||
|
|
||||||
|
x_rotation_center = int((box[0][0][0] + box[1][0][0] + box[2][0][0] + box[3][0][0]) / 4)
|
||||||
|
y_rotation_center = int((box[0][0][1] + box[1][0][1] + box[2][0][1] + box[3][0][1]) / 4)
|
||||||
|
point_x, point_y, point_z = pm[y_rotation_center, x_rotation_center]
|
||||||
|
cv2.circle(img, (x_rotation_center, y_rotation_center), 4, (255, 255, 255), 5) # 标出中心点
|
||||||
|
if np.isnan(point_x): # 点云值为无效值
|
||||||
|
continue
|
||||||
|
else:
|
||||||
|
xyz.append([point_x*1000, point_y*1000, point_z*1000])
|
||||||
|
Depth_Z.append(point_z*1000)
|
||||||
|
nx_ny_nz.append([a, b, c])
|
||||||
|
RegionalArea.append(cv2.contourArea(max_contour))
|
||||||
|
uv.append([x_rotation_center, y_rotation_center])
|
||||||
|
seg_point.append(pm_seg)
|
||||||
|
cv2.polylines(img, [box], True, (0, 255, 0), 2)
|
||||||
|
|
||||||
|
_idx = find_position(Depth_Z, RegionalArea, 100,True)
|
||||||
|
|
||||||
|
if _idx == None:
|
||||||
|
return 1, img, None, None
|
||||||
|
else:
|
||||||
|
cv2.circle(img, (uv[_idx][0], uv[_idx][1]), 30, (255, 0, 0), 20) # 标出中心点
|
||||||
|
|
||||||
|
if Point_isVision==True:
|
||||||
|
pcd = o3d.geometry.PointCloud()
|
||||||
|
pcd.points = o3d.utility.Vector3dVector(seg_point[_idx])
|
||||||
|
plane_model, inliers = pcd.segment_plane(distance_threshold=0.01,
|
||||||
|
ransac_n=5,
|
||||||
|
num_iterations=5000)
|
||||||
|
inlier_cloud = pcd.select_by_index(inliers) # 点云可视化
|
||||||
|
inlier_cloud.paint_uniform_color([1.0, 0, 0])
|
||||||
|
outlier_cloud = pcd.select_by_index(inliers, invert=True)
|
||||||
|
outlier_cloud.paint_uniform_color([0, 1, 0])
|
||||||
|
o3d.visualization.draw_geometries([inlier_cloud, outlier_cloud, pcd2])
|
||||||
|
|
||||||
|
return 1, img, xyz[_idx], nx_ny_nz[_idx]
|
||||||
|
else:
|
||||||
|
return 1, img, None, None
|
||||||
|
|
||||||
return 1, img, xyz[_idx], nx_ny_nz[_idx]
|
|
||||||
else:
|
else:
|
||||||
return 1, img, None, None
|
print("RVC X Camera capture failed!")
|
||||||
|
return 0, None, None, None
|
||||||
|
|
||||||
else:
|
else:
|
||||||
print("RVC X Camera capture failed!")
|
print("RVC X Camera is not opened!")
|
||||||
return 0, None, None, None
|
return 0, None, None, None
|
||||||
|
|
||||||
def release(self):
|
def release(self):
|
||||||
|
self.camera_rvc.release()
|
||||||
self.model.clear()
|
self.model.clear()
|
||||||
|
|
||||||
|
|
||||||
|
|||||||
@ -54,7 +54,6 @@ class Detection:
|
|||||||
flag, det_cpu, dst_img, masks, category_names = self.model.model_inference(img, 0)
|
flag, det_cpu, dst_img, masks, category_names = self.model.model_inference(img, 0)
|
||||||
else:
|
else:
|
||||||
flag, det_cpu, scores, masks, category_names = self.model.segment_objects(img)
|
flag, det_cpu, scores, masks, category_names = self.model.segment_objects(img)
|
||||||
dst_img = img
|
|
||||||
if flag == 1:
|
if flag == 1:
|
||||||
xyz = []
|
xyz = []
|
||||||
nx_ny_nz = []
|
nx_ny_nz = []
|
||||||
@ -132,6 +131,9 @@ class Detection:
|
|||||||
select_point = np.array(select_point)
|
select_point = np.array(select_point)
|
||||||
pm_seg = select_point.reshape(-1, 3)
|
pm_seg = select_point.reshape(-1, 3)
|
||||||
pm_seg = pm_seg[~np.isnan(pm_seg).all(axis=-1), :] # 剔除 nan
|
pm_seg = pm_seg[~np.isnan(pm_seg).all(axis=-1), :] # 剔除 nan
|
||||||
|
if pm_seg.size < 300:
|
||||||
|
print("分割点云数量较少,无法拟合平面")
|
||||||
|
continue
|
||||||
# cv2.imshow('result', piont_result)
|
# cv2.imshow('result', piont_result)
|
||||||
|
|
||||||
'''
|
'''
|
||||||
|
|||||||
Reference in New Issue
Block a user