相關(guān)鏈接
此項目直接調(diào)用zed相機實現(xiàn)三維測距,無需標定,相關(guān)內(nèi)容如下:
1.yolov5直接調(diào)用zed相機實現(xiàn)三維測距(python)
2. yolov4直接調(diào)用zed相機實現(xiàn)三維測距
3. Windows+YOLOV8環(huán)境配置
4.具體實現(xiàn)效果已在嗶哩嗶哩發(fā)布,點擊此鏈接跳轉(zhuǎn)
本篇博文工程源碼下載(麻煩github給個星星)
下載鏈接:https://github.com/up-up-up-up/zed-yolov8
附:Zed調(diào)用YOLOv7測距也已經(jīng)實現(xiàn),但是3060筆記本6G顯存帶不動,在大現(xiàn)存服務(wù)器上可以運行,可能是由于YOLOv7網(wǎng)絡(luò)結(jié)構(gòu)導致的,由于不具備普適性,就不再寫相關(guān)文章了,有需要的可以仿照這個代碼去改寫
1. 相關(guān)配置
python==3.7
Windows-pycharm
zed api 具體配置見 (zed api 配置步驟)
由于我電腦之前python版本為3.7,yolov8要求python最低為3.8,所以本次實驗直接在虛擬環(huán)境里進行,未配置gpu,可能看著卡卡的,有需要的可以配置一下,原理是一樣的
2. 版本一
2.1 相關(guān)代碼
主代碼 zed-yolo.py,具體放置在yolov8主目錄下,盒子形式展現(xiàn),可實現(xiàn)測距+跟蹤
#!/usr/bin/env python3
import sys
import numpy as np
import argparse
import torch
import cv2
import pyzed.sl as sl
from ultralytics import YOLO
from threading import Lock, Thread
from time import sleep
import ogl_viewer.viewer as gl
import cv_viewer.tracking_viewer as cv_viewer
lock = Lock()
run_signal = False
exit_signal = False
def xywh2abcd(xywh, im_shape):
output = np.zeros((4, 2))
# Center / Width / Height -> BBox corners coordinates
x_min = (xywh[0] - 0.5*xywh[2]) #* im_shape[1]
x_max = (xywh[0] + 0.5*xywh[2]) #* im_shape[1]
y_min = (xywh[1] - 0.5*xywh[3]) #* im_shape[0]
y_max = (xywh[1] + 0.5*xywh[3]) #* im_shape[0]
# A ------ B
# | Object |
# D ------ C
output[0][0] = x_min
output[0][1] = y_min
output[1][0] = x_max
output[1][1] = y_min
output[2][0] = x_max
output[2][1] = y_max
output[3][0] = x_min
output[3][1] = y_max
return output
def detections_to_custom_box(detections, im0):
output = []
for i, det in enumerate(detections):
xywh = det.xywh[0]
# Creating ingestable objects for the ZED SDK
obj = sl.CustomBoxObjectData()
obj.bounding_box_2d = xywh2abcd(xywh, im0.shape)
obj.label = det.cls
obj.probability = det.conf
obj.is_grounded = False
output.append(obj)
return output
def torch_thread(weights, img_size, conf_thres=0.2, iou_thres=0.45):
global image_net, exit_signal, run_signal, detections
print("Intializing Network...")
model = YOLO(weights)
while not exit_signal:
if run_signal:
lock.acquire()
img = cv2.cvtColor(image_net, cv2.COLOR_BGRA2RGB)
# https://docs.ultralytics.com/modes/predict/#video-suffixes
det = model.predict(img, save=False, imgsz=img_size, conf=conf_thres, iou=iou_thres)[0].cpu().numpy().boxes
# ZED CustomBox format (with inverse letterboxing tf applied)
detections = detections_to_custom_box(det, image_net)
lock.release()
run_signal = False
sleep(0.01)
def main():
global image_net, exit_signal, run_signal, detections
capture_thread = Thread(target=torch_thread, kwargs={'weights': opt.weights, 'img_size': opt.img_size, "conf_thres": opt.conf_thres})
capture_thread.start()
print("Initializing Camera...")
zed = sl.Camera()
input_type = sl.InputType()
if opt.svo is not None:
input_type.set_from_svo_file(opt.svo)
# Create a InitParameters object and set configuration parameters
init_params = sl.InitParameters(input_t=input_type, svo_real_time_mode=True)
init_params.coordinate_units = sl.UNIT.METER
init_params.depth_mode = sl.DEPTH_MODE.ULTRA # QUALITY
init_params.coordinate_system = sl.COORDINATE_SYSTEM.RIGHT_HANDED_Y_UP
init_params.depth_maximum_distance = 50
runtime_params = sl.RuntimeParameters()
status = zed.open(init_params)
if status != sl.ERROR_CODE.SUCCESS:
print(repr(status))
exit()
image_left_tmp = sl.Mat()
print("Initialized Camera")
positional_tracking_parameters = sl.PositionalTrackingParameters()
# If the camera is static, uncomment the following line to have better performances and boxes sticked to the ground.
# positional_tracking_parameters.set_as_static = True
zed.enable_positional_tracking(positional_tracking_parameters)
obj_param = sl.ObjectDetectionParameters()
# obj_param.detection_model = sl.OBJECT_DETECTION_MODEL.CUSTOM_BOX_OBJECTS
obj_param.enable_tracking = True
zed.enable_object_detection(obj_param)
objects = sl.Objects()
obj_runtime_param = sl.ObjectDetectionRuntimeParameters()
# Display
camera_infos = zed.get_camera_information()
camera_res = camera_infos.camera_resolution
# Create OpenGL viewer
viewer = gl.GLViewer()
point_cloud_res = sl.Resolution(min(camera_res.width, 720), min(camera_res.height, 404))
point_cloud_render = sl.Mat()
viewer.init(camera_infos.camera_model, point_cloud_res, obj_param.enable_tracking)
point_cloud = sl.Mat(point_cloud_res.width, point_cloud_res.height, sl.MAT_TYPE.F32_C4, sl.MEM.CPU)
image_left = sl.Mat()
# Utilities for 2D display
display_resolution = sl.Resolution(min(camera_res.width, 1280), min(camera_res.height, 720))
image_scale = [display_resolution.width / camera_res.width, display_resolution.height / camera_res.height]
image_left_ocv = np.full((display_resolution.height, display_resolution.width, 4), [245, 239, 239, 255], np.uint8)
# # Utilities for tracks view
# camera_config = camera_infos.camera_configuration
# tracks_resolution = sl.Resolution(400, display_resolution.height)
# track_view_generator = cv_viewer.TrackingViewer(tracks_resolution, camera_config.fps, init_params.depth_maximum_distance)
# track_view_generator.set_camera_calibration(camera_config.calibration_parameters)
# image_track_ocv = np.zeros((tracks_resolution.height, tracks_resolution.width, 4), np.uint8)
# Camera pose
cam_w_pose = sl.Pose()
while viewer.is_available() and not exit_signal:
if zed.grab(runtime_params) == sl.ERROR_CODE.SUCCESS:
# -- Get the image
lock.acquire()
zed.retrieve_image(image_left_tmp, sl.VIEW.LEFT)
image_net = image_left_tmp.get_data()
lock.release()
run_signal = True
# -- Detection running on the other thread
while run_signal:
sleep(0.001)
# Wait for detections
lock.acquire()
# -- Ingest detections
zed.ingest_custom_box_objects(detections)
lock.release()
zed.retrieve_objects(objects, obj_runtime_param)
# -- Display
# Retrieve display data
zed.retrieve_measure(point_cloud, sl.MEASURE.XYZRGBA, sl.MEM.CPU, point_cloud_res)
point_cloud.copy_to(point_cloud_render)
zed.retrieve_image(image_left, sl.VIEW.LEFT, sl.MEM.CPU, display_resolution)
zed.get_position(cam_w_pose, sl.REFERENCE_FRAME.WORLD)
# 3D rendering
viewer.updateData(point_cloud_render, objects)
# 2D rendering
np.copyto(image_left_ocv, image_left.get_data())
cv_viewer.render_2D(image_left_ocv, image_scale, objects, obj_param.enable_tracking)
global_image = image_left_ocv
# global_image = cv2.hconcat([image_left_ocv, image_track_ocv])
# # Tracking view
# track_view_generator.generate_view(objects, cam_w_pose, image_track_ocv, objects.is_tracked)
cv2.imshow("ZED | 2D View and Birds View", global_image)
key = cv2.waitKey(10)
if key == 27:
exit_signal = True
else:
exit_signal = True
viewer.exit()
exit_signal = True
zed.close()
if __name__ == '__main__':
parser = argparse.ArgumentParser()
parser.add_argument('--weights', type=str, default='yolov8n.pt', help='model.pt path(s)')
parser.add_argument('--svo', type=str, default=None, help='optional svo file')
parser.add_argument('--img_size', type=int, default=416, help='inference size (pixels)')
parser.add_argument('--conf_thres', type=float, default=0.4, help='object confidence threshold')
opt = parser.parse_args()
with torch.no_grad():
main()
2.2 實驗結(jié)果
測距圖(感覺挺精準的)
視頻展示:
Zed相機+YOLOv8目標檢測跟蹤
3. 版本二
3.1 相關(guān)代碼
主代碼 zed.py,具體放置在yolov8主目錄下,可實現(xiàn)測距+跟蹤+分割,完整代碼六月開源
#!/usr/bin/env python3
import math
import sys
import numpy as np
from PIL import Image
import argparse
import torch
import cv2
import pyzed.sl as sl
from ultralytics.utils.plotting import Annotator, colors, save_one_box
from ultralytics import YOLO
from threading import Lock, Thread
from time import sleep
import ogl_viewer.viewer as gl
import cv_viewer.tracking_viewer as cv_viewer
zed = sl.Camera()
# Create a InitParameters object and set configuration parameters
init_params = sl.InitParameters()
init_params.camera_resolution = sl.RESOLUTION.HD720
init_params.coordinate_units = sl.UNIT.METER
init_params.depth_mode = sl.DEPTH_MODE.ULTRA # QUALITY
init_params.coordinate_system = sl.COORDINATE_SYSTEM.RIGHT_HANDED_Y_UP
init_params.depth_maximum_distance = 20 # 設(shè)置最遠距離
runtime_params = sl.RuntimeParameters()
status = zed.open(init_params)
if status != sl.ERROR_CODE.SUCCESS:
print(repr(status))
exit()
image_left_tmp = sl.Mat()
print("Initialized Camera")
positional_tracking_parameters = sl.PositionalTrackingParameters()
zed.enable_positional_tracking(positional_tracking_parameters)
obj_param = sl.ObjectDetectionParameters()
obj_param.detection_model = sl.DETECTION_MODEL.CUSTOM_BOX_OBJECTS
obj_param.enable_tracking = True
zed.enable_object_detection(obj_param)
objects = sl.Objects()
obj_runtime_param = sl.ObjectDetectionRuntimeParameters()
point_cloud_render = sl.Mat()
point_cloud = sl.Mat()
image_left = sl.Mat()
depth = sl.Mat()
# Utilities for 2D display
3.2 實驗結(jié)果
可實現(xiàn)測距、跟蹤和分割功能,這個代碼沒有加多線程,速度夠用懶得寫了,對速率要求高的可以自己寫一下,實現(xiàn)不同功能僅需修改以下代碼,具體見 此篇文章
model = YOLO("./yolov8n.pt")
img = cv2.cvtColor(image_net, cv2.COLOR_BGRA2BGR)
result = model.predict(img, conf=0.5)
測距功能
跟蹤功能文章來源:http://www.zghlxwxcb.cn/news/detail-847850.html
分割功能
視頻展示文章來源地址http://www.zghlxwxcb.cn/news/detail-847850.html
到了這里,關(guān)于yolov8直接調(diào)用zed相機實現(xiàn)三維測距(python)的文章就介紹完了。如果您還想了解更多內(nèi)容,請在右上角搜索TOY模板網(wǎng)以前的文章或繼續(xù)瀏覽下面的相關(guān)文章,希望大家以后多多支持TOY模板網(wǎng)!