Vision_

Opencv_StereoBM 을 사용한 stereo matching

대장장ㅇi 2024. 8. 29. 14:38

StereoBM_원리

OpenCV에서 사용하는 StereoBM(Stereo Block Matching) 알고리즘은 스테레오 비전에서 두 장의 이미지(일반적으로 왼쪽과 오른쪽 카메라에서 촬영된 이미지) 간의 시차(disparity)를 계산하기 위한 방법이다. 이 시차는 각 픽셀이 두 이미지에서 차지하는 위치 차이로, 이를 이용해 거리 정보를 추출할 수 있다. StereoBM의 기본 원리는 블록 매칭(Block Matching)이라고 불리며, 다음과 같은 단계로 요약할 수 있다:

1. blocksize 정의:

  • 입력 이미지는 작은 블록(또는 윈도우)으로 나눈다. 블록 크기는 사용자가 설정할 수 있으며, 일반적으로 5x5, 7x7 같은 정사각형 크기가 많이 사용됩니다.

2. block 매칭:

  • 왼쪽 이미지에서 선택된 각 블록에 대해 오른쪽 이미지의 해당 행에서 유사한 블록을 찾는다. 이 과정에서 블록의 위치는 왼쪽 이미지와 동일한 위치에서 시작해 일정 범위 내에서 오른쪽으로 이동한다. 이동 범위는 검색할 시차 범위에 따라 결정된다.

3. 비용 함수 계산:

  • 두 블록 간의 유사성을 평가하기 위해 비용 함수를 계산합니다. 가장 일반적인 비용 함수는 두 블록의 픽셀 간 차이의 절대값을 합산하는 **SAD(Sum of Absolute Differences)**이다. 이외에도 SSD(Sum of Squared Differences) 등이 사용될 수 있습니다.

4. 최소 비용 찾기:

  • 위에서 계산된 비용 함수 값 중 가장 작은 값을 가지는 블록을 선택한다. 이때의 블록 위치 차이가 해당 픽셀의 시차로 설정된다.

5. 시차 맵 생성:

  • 모든 픽셀에 대해 시차 계산을 완료한 후, 이를 이용해 시차 맵(disparity map)을 생성한다. 시차 맵은 각 픽셀의 시차 값을 시각적으로 표현한 것이다.

 

 

StereoBM_실습코드

    def process_images(self):
        if self.left_image is not None and self.right_image is not None:
            # 이미지를 gray scale 로 변환. stereo matching 을 위해서는 흑백 이미지 필요.
            gray_left = cv2.cvtColor(self.left_image, cv2.COLOR_BGR2GRAY)
            gray_right = cv2.cvtColor(self.right_image, cv2.COLOR_BGR2GRAY)

            # 블록 매칭을 위한 초기화
            stereo = cv2.StereoBM_create(numDisparities=16, blockSize=7)
            disparity = stereo.compute(gray_left, gray_right)

            # 깊이 정보 시각화
            disparity_normalized = cv2.normalize(disparity, None, 0, 255, cv2.NORM_MINMAX, cv2.CV_8U)
            cv2.imshow("Disparity", disparity_normalized)
            cv2.waitKey(1)

 

 

#!/usr/bin/env python3

import rclpy
from rclpy.node import Node
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
import numpy as np

class CameraFusionNode(Node):
    def __init__(self):
        super().__init__('camera_fusion_node')
        self.bridge = CvBridge()

        # 두 카메라의 이미지를 구독.
        self.left_image_sub = self.create_subscription(
            Image, 'left_camera/image_raw', self.left_image_callback, 10)
        self.right_image_sub = self.create_subscription(
            Image, 'right_camera/image_raw', self.right_image_callback, 10)

        self.left_image = None
        self.right_image = None

    def left_image_callback(self, msg):
        self.left_image = self.bridge.imgmsg_to_cv2(msg, "bgr8")
        self.process_images()

    def right_image_callback(self, msg):
        self.right_image = self.bridge.imgmsg_to_cv2(msg, "bgr8")
        self.process_images()

    def process_images(self):
        if self.left_image is not None and self.right_image is not None:
            # 이미지를 gray scale 로 변환. stereo matching 을 위해서는 흑백 이미지 필요.
            gray_left = cv2.cvtColor(self.left_image, cv2.COLOR_BGR2GRAY)
            gray_right = cv2.cvtColor(self.right_image, cv2.COLOR_BGR2GRAY)

            # 블록 매칭을 위한 초기화
            stereo = cv2.StereoBM_create(numDisparities=16, blockSize=15)
            disparity = stereo.compute(gray_left, gray_right)

            # 깊이 정보 시각화
            disparity_normalized = cv2.normalize(disparity, None, 0, 255, cv2.NORM_MINMAX, cv2.CV_8U)
            cv2.imshow("Disparity", disparity_normalized)
            cv2.waitKey(1)

def main(args=None):
    rclpy.init(args=args)
    node = CameraFusionNode()
    rclpy.spin(node)
    node.destroy_node()
    rclpy.shutdown()

if __name__ == '__main__':
    main()