目录
一、depthai ROS驱动
一、depthai ROS驱动
(1)驱动下载地址:2. C++ 开发快速上手 — DepthAI Docs 0.3.0.0 documentation
sudo apt install ./depthai_2.17.1_arm64.deb
//运行
Python3 utilities/cam_test.py -mres 400 -cams rgb,m left,m right,m camd,m
(2)或者运行python脚本打开相机
import depthai as dai
import cv2cam_list = ["CAM_B", "CAM_C", "CAM_D","CAM_A"]
cam_socket_opts = {"CAM_A": dai.CameraBoardSocket.RGB,"CAM_B": dai.CameraBoardSocket.LEFT,"CAM_C": dai.CameraBoardSocket.RIGHT,"CAM_D": dai.CameraBoardSocket.CAM_D,
}pipeline = dai.Pipeline()
cam = {}
xout = {}
for c in cam_list:cam[c] = pipeline.create(dai.node.MonoCamera)cam[c].setResolution(dai.MonoCameraProperties.SensorResolution.THE_800_P)if c == "CAM_A":cam[c].initialControl.setFrameSyncMode(dai.CameraControl.FrameSyncMode.OUTPUT)else:cam[c].initialControl.setFrameSyncMode(dai.CameraControl.FrameSyncMode.INPUT)# cam[c].initialControl.setExternalTrigger(4, 3)cam[c].setBoardSocket(cam_socket_opts[c])cam[c].setFps(20)xout[c] = pipeline.create(dai.node.XLinkOut)xout[c].setStreamName(c)cam[c].out.link(xout[c].input)config = dai.Device.Config()
config.board.gpio[6] = dai.BoardConfig.GPIO(dai.BoardConfig.GPIO.OUTPUT, dai.BoardConfig.GPIO.Level.HIGH
)
# config.version = dai.OpenVINO.VERSION_UNIVERSALwith dai.Device(config) as device:device.startPipeline(pipeline)print('Connected cameras:')for p in device.getConnectedCameraFeatures():print(f' -socket {p.socket.name:6}: {p.sensorName:6} {p.width:4} x {p.height:4} focus:', end='')print('auto ' if p.hasAutofocus else 'fixed', '- ', end='')print(*[type.name for type in p.supportedTypes])q = {}for c in cam_list:q[c] = device.getOutputQueue(name=c, maxSize=1, blocking=False)cv2.namedWindow(c, cv2.WINDOW_NORMAL)cv2.resizeWindow(c, (640, 480))while not device.isClosed():git clone https://github.com/ethz-asl/kalibr.gitframe_list = []for c in cam_list:pkt = q[c].tryGet()if pkt is not None:print(c + ":", pkt.getTimestampDevice())frame_list.append((c, pkt.getCvFrame()))# cv2.imshow(c, frame)if frame_list:print("-------------------------------")for c,frame in frame_list:cv2.imshow(c, frame)#print("-------------------------------")key = cv2.waitKey(1)if key == ord("q"):break
(3)使用python脚本
'''func:驱动DepthAi套件的相机by:2024.7.5
'''
import depthai as dai
import cv2
import queue
class CamerDrive():cam_list = ['rgb', 'left', 'right', 'camd']cam_socket_opts = {}pipeline = dai.Pipeline()# 初始化两个字典,用于存储摄像头节点和XLinkOut节点cam = {}xout = {}#frameQueue = {}device = None# myFrameQueue = {}# 构造函数def __init__(self):self.cam_socket_opts = {'rgb': dai.CameraBoardSocket.RGB, # Or CAM_A 板载接口名称可复用'left': dai.CameraBoardSocket.LEFT, # Or CAM_B'right': dai.CameraBoardSocket.RIGHT, # Or CAM_C'camd': dai.CameraBoardSocket.CAM_D,}# 配置相机节点def cameraNodeConfig(self):for c in self.cam_list:# 创建MonoCamera节点(注意:这里可能对于RGB摄像头需要改为ColorCamera)self.cam[c] = self.pipeline.create(dai.node.MonoCamera)# if c == 'rgb':# self.cam[c] = self.pipeline.create(dai.node.ColorCamera)# 设置摄像头分辨率为800Pself.cam[c].setResolution(dai.MonoCameraProperties.SensorResolution.THE_800_P)# 根据摄像头类型设置帧同步模式if c == 'rgb':self.cam[c].initialControl.setFrameSyncMode(dai.CameraControl.FrameSyncMode.OUTPUT) # 输出同步模式else:self.cam[c].initialControl.setFrameSyncMode(dai.CameraControl.FrameSyncMode.INPUT) # 输入同步模式# 设置摄像头连接到板载的哪个接口self.cam[c].setBoardSocket(self.cam_socket_opts[c])# 创建XLinkOut节点,用于将摄像头数据输出到主机self.xout[c] = self.pipeline.create(dai.node.XLinkOut)# 设置输出流的名称self.xout[c].setStreamName(c)# 将摄像头的输出链接到XLinkOut的输入self.cam[c].out.link(self.xout[c].input)def depthAIConfig(self):config = dai.Device.Config()# 将GPIO引脚6配置为输出模式,并设置初始电平为高config.board.gpio[6] = dai.BoardConfig.GPIO(dai.BoardConfig.GPIO.OUTPUT,dai.BoardConfig.GPIO.Level.HIGH)# 使用Device类创建一个设备实例,并传入之前配置的配置对象。同时,使用with语句确保设备在使用完毕后正确关闭。# with dai.Device(config) as device:self.device = dai.Device(config)# 启动pipeline对象self.device.startPipeline(self.pipeline)# 遍历相机列表,为每个相机设置输出队列、OpenCV窗口,并初始化FPS计算对象。for c in self.cam_list:self.frameQueue[c] = self.device.getOutputQueue(name=c, maxSize=1, blocking=False) # 获取相机输出队列,非阻塞模式cv2.namedWindow(c, cv2.WINDOW_NORMAL) # 为每个相机创建一个OpenCV窗口cv2.resizeWindow(c, (640, 480)) # 调整窗口大小def get_Frame(self):while True:for c in self.cam_list:# 尝试从输出队列中获取一帧数据。try:pkt = self.frameQueue[c].tryGet()if pkt is not None:# 将数据包转换为OpenCV的Mat对象并显示。frame = pkt.getCvFrame()cv2.imshow(c, frame)else:print('sda')key = cv2.waitKey(1)if key == ord('q'):breakexcept:passif __name__ == '__main__':a = CamerDrive()a.cameraNodeConfig()a.depthAIConfig()a.get_Frame()
二、获取相机内参
1.安装depthai-ros
mkdir -p dai_ws/src
cd dai_ws/src
git clone https://gitee.com/oakchina/depthai-ros.git
cd ..
source /opt/ros/melodic/setup.bash
rosdep install --from-paths src --ignore-src -r -y
catkin_make
source devel/setup.bash
2.执行相机对应的launch文件
cd dai_ws
source devel/setup.bash
roslaunch depthai_examples mobile_publisher.launch camera_model:=OAK-D
3.查看相机内参
rostopic echo -n 1 /mobilenet_publisher/color/camera_info
4.相机内参结果
相机内参Intrinsics: k表示等距畸变系数,mu,mv对应焦距,v,u对应主点坐标。 相机外参Extrinsics(从右目往左目): rotation表示旋转矩阵, translation表示平移矩阵。 D、K、R、P 分别为畸变参数,内参矩阵,矫正矩阵,投影矩阵。 seq: 0 stamp: secs: 1719912958 nsecs: 823117551 frame_id: "oak_rgb_camera_optical_frame" height: 720 width: 1280 distortion_model: "plumb_bob" 畸变参数D: [-1.87286, 16.683033, 0.001053, -0.002063, 61.878521, -2.158907, 18.424637, 57.682858, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0] 内参矩阵 K: [1479.458984, 0.0, 950.694458, 0.0, 1477.587158, 530.697632, 0.0, 0.0, 1.0] R: [0.9997062937394856, -0.023389961528659683, 0.006343181957754751, 0.0233922879452606, 0.999726320114537, -0.0002928052810344399, -0.006334597252184302, 0.0004411008211352551, 0.9999798389506251] P: [1479.458984, 0.0, 950.694458, 0.0, 0.0, 1477.587158, 530.697632, 0.0, 0.0, 0.0, 1.0, 0.0] binning_x: 0 binning_y: 0 roi: x_offset: 0 y_offset: 0 height: 0 width: 0 do_rectify: False --- |
三、OAK相机外参
git clone https://gitee.com/oakchina/depthai.git
python3 install_requirements.py
//运行
python3 calibrate.py -s 2.75 -ms 2.05 -brd OAK-D -cd 0 -c 1 -mst 1
-db
:表示默认板,表示你正在使用
Charuco
标记。
-
-nx:x 方向上的 Charuco 标记数。
-
-c:每次显示多边形时拍摄的照片数量(可选,建议在你的情况下省略)。
-
-cd:拍摄照片前的倒计时时间(以秒为单位)(可选,建议用于更快的图像校准)。
-
-s:Charuco 标记周围的正方形大小(以厘米为单位)。
-
-ms:标记的大小(以厘米为单位)。
-
-brd:设备的板(在本例中为 OAK-D-SR-POE)
修改其json文件
{"board_config":{"name": "OAK-D","revision": "R1M0E1","cameras":{"CAM_A": {"name": "rgb","hfov": 89.5水平视场角"type": "color"相机类型},"CAM_B": {"name": "left","hfov": 71.86,"type": "mono","extrinsics": {"to_cam": "CAM_C","specTranslation": {"x": -7.5,"y": 0,"z": 0},"rotation":{"r": 0,"p": 0,"y": 0}}},"CAM_C": {"name": "right","hfov": 71.86,"type": "mono","extrinsics": {"to_cam": "CAM_A","specTranslation": {"x": 3.75,"y": 0,"z": 0},"rotation":{"r": 0,"p": 0,"y": 0}}}},"stereo_config":{"left_cam": "CAM_B","right_cam": "CAM_C"}}
}
标定结果