🚀Project🚀/Navigation with detecting person

[Project1] - (2) ROS2와 YOLOv8 연동시키기

고집호랑이 2023. 5. 1. 07:13

이제 YOLOv8을 사용하기로 결정했으니 ROS2와 연동하여 사람을 detect할 수 있게 만들어야 합니다. 

 

카메라를 통한 이미지 topic을 받은 후(subscribe)에 YOLOv8로 object를 detect한 후 그 결과를 navigation이 사용할 수 있도록 publish해줘야 하죠. 

 

따라서 저는 topic을 보내고 받는 역할을 수행하기 위해 node와 이 node를 실행시킬 launch 파일이 필요합니다.

 

YOLOv7까지는 이를 자동으로 만들어 ROS와 연동시켜주는 darknet_ros 라는 패키지가 존재하나 제가 사용할 YOLOv8은 나온지 얼마되지 않아서인지 지원하지 않았습니다. 

 

node와 launch 파일을 직접 만들어야하는 머리 아픈 상황에서 혹시나 하는 마음으로 github를 뒤져본 결과, ROS2와 YOLOv8을 연동시켜 주는 아래 github를 발견했습니다. (만드신 개발자분 만세!! 🙌)

 

https://github.com/mgonzs13/yolov8_ros

 

GitHub - mgonzs13/yolov8_ros: YOLOv8 for ROS 2 using ultralytics (https://github.com/ultralytics/ultralytics)

YOLOv8 for ROS 2 using ultralytics (https://github.com/ultralytics/ultralytics) - GitHub - mgonzs13/yolov8_ros: YOLOv8 for ROS 2 using ultralytics (https://github.com/ultralytics/ultralytics)

github.com

 

간단한 코드 설명

이미 만들어져 있다고는 해도 이 패키지를 사용하고 목적에 맞게 수정하기 위해서는 코드가 어떻게 구성되어 있는지는 알아야합니다. 

 

node 파일과 launch 파일코드에 대해서 간단히 설명하도록 하겠습니다. 

 

node 파일은 yolov8_ros/yolov8_ros/yolov8_node.py 에, launch 파일은 yolov8_ros/yolov8_bringup/launch/yolov8.launch.py 에 존재합니다.

 

yolov8_node.py

1) parameter값 선언 

class Yolov8Node(Node):

    def __init__(self) -> None:
        super().__init__("yolov8_node")

        # params
        self.declare_parameter("model", "yolov8m.pt")
        model = self.get_parameter(
            "model").get_parameter_value().string_value

        self.declare_parameter("tracker", "bytetrack.yaml")
        tracker = self.get_parameter(
            "tracker").get_parameter_value().string_value

        self.declare_parameter("device", "cuda:0")
        device = self.get_parameter(
            "device").get_parameter_value().string_value

        self.declare_parameter("threshold", 0.5)
        self.threshold = self.get_parameter(
            "threshold").get_parameter_value().double_value
                                 .
                                 .
                                 .

YOLOv8에 사용될 parameter 값을 선언하는 부분입니다. 사용할 pretrained 모델, object tracking 방법, YOLOv8의 연산을 수행할 device 그리고 confidence threshold값에 대한 parameter 값 등을 선언하고 있습니다. 

 

여기서는 다음과 같은 parameter 값을 사용하는 것을 확인할 수 있습니다.

  • COCO dataset으로 pretrained 된 yolov8m 모델 (yolov8m.pt)
  • bytetrack을 이용하여 객체를 tracking (bytetrack.yaml)
  • GPU 0번 사용 (cuda:0)
  • Confidence score가 0.5를 넘는 객체들만 detect (0.5)

 

다른 YOLOv8 모델이나 tracking 방법을 사용하고 싶다면 이 parameter 값들을 조절하면 원하는 목적에 맞게 사용할 수 있겠습니다.

 

2) publisher와 subscriber 생성

# topcis
self._pub = self.create_publisher(Detection2DArray, "detections", 10)
self._dbg_pub = self.create_publisher(Image, "dbg_image", 10)
self._sub = self.create_subscription(
    Image, "image_raw", self.image_cb,
    qos_profile_sensor_data
)

"detections" 이라는 topic으로 객체를 detect한 결과 정보를 publish해주고 "dbg_image" topic으로는 결과를 pixel 값으로 publish 해주는 publisher을 생성해줍니다.

 

그리고 "image_raw"라는 topic을 subscribe하면 image_cb 함수를 실행시키는 subscriber도 생성해줍니다. 카메라가 publish하는 이미지 topic에 맞게 "image_raw"도 변경하면 됩니다.  

 

이후 코드에서는 subscribe한 "image_raw" topic에서 YOLOv8로 객체를 detect해주고 그 결과를 "detections"과 "dbg_image" topic에 담은 후 publish해주는 코드가 나올 것을 예상할 수 있을 것입니다.

 

3) subscribe한 이미지에 YOLOv8 적용

def image_cb(self, msg: Image) -> None:

    if self.enable:

        # convert image + predict
        cv_image = self.cv_bridge.imgmsg_to_cv2(msg)
        results = self.yolo.predict(
            source=cv_image,
            verbose=False,
            stream=False,
            conf=0.1,
            mode="track"
        )

이미지 topic인 "image_raw"를 subscribe하면 image_cb 함수를 시켜 입력 이미지에서 YOLOv8로 객체를 detect합니다.

 

4) 이미지에 bounding box, class label 및 confidence score 표시

# draw boxes for debug
if label not in self._class_to_color:
    r = random.randint(0, 255)
    g = random.randint(0, 255)
    b = random.randint(0, 255)
    self._class_to_color[label] = (r, g, b)
color = self._class_to_color[label]

min_pt = (round(detection.bbox.center.position.x - detection.bbox.size_x / 2.0),
          round(detection.bbox.center.position.y - detection.bbox.size_y / 2.0))
max_pt = (round(detection.bbox.center.position.x + detection.bbox.size_x / 2.0),
          round(detection.bbox.center.position.y + detection.bbox.size_y / 2.0))
cv2.rectangle(cv_image, min_pt, max_pt, color, 2)

label = "{} ({}) ({:.3f})".format(label, str(track_id), score)
pos = (min_pt[0] + 5, min_pt[1] + 25)
font = cv2.FONT_HERSHEY_SIMPLEX
cv2.putText(cv_image, label, pos, font,
            1, color, 1, cv2.LINE_AA)

# append msg
detections_msg.detections.append(detection)

이미지에 Bounding box와 Class label 그리고 Confidence score을 표시하고 detect 결과들을 publish할 "detections" topic에 저장하는 코드입니다.

 

yolov8.launch.py

1) 사용할 구성 변수 설정 및 변수들의 인자 정의

def generate_launch_description():
    model = LaunchConfiguration("model")
    model_cmd = DeclareLaunchArgument(
        "model",
        default_value="yolov8m.pt",
        description="Model name or path")

    tracker = LaunchConfiguration("tracker")
    tracker_cmd = DeclareLaunchArgument(
        "tracker",
        default_value="bytetrack.yaml",
        description="Tracker name or path")

    device = LaunchConfiguration("device")
    device_cmd = DeclareLaunchArgument(
        "device",
        default_value="cuda:0",
        description="Device to use (GPU/CPU)")
                            .
                            .
                            .

launch 파일에 사용할 구성 변수의 이름 설정을 설정하고 그 변수들의 default 값과 설명 등을 정의해주는 부분입니다.

 

사용할 model, tracking 방법, 연산을 수행할 device 등에 관한 변수를 설정하고 이 변수들의 default 값과 설명(description)을 정의해주고 있습니다.

 

2) Node 설정

detector_node_cmd = Node(
    package="yolov8_ros",
    executable="yolov8_node",
    name="yolov8_node",
    namespace=namespace,
    parameters=[{"model": model,
                 "tracker": tracker,
                 "device": device,
                 "enable": enable,
                 "threshold": threshold}],
    remappings=[("image_raw", input_image_topic)]
)

사용할 Node에 대해서 설정하는 부분입니다. node의 이름과 사용한 패키지와 더불어 위에서 정의한 변수들을 이용해 yolov8을 사용하기 위해 필요한 parameter와 topic을 설정해줍니다.

 

코드 일부분만 발췌해서 설명했기 때문에 더 깊게 살펴보고 싶으신 분은 위 github 링크를 통해서 전체 코드를 확인하시기 바랍니다.

 

자 이제 패키지를 제 컴퓨터에 설치하고 실행시켜 봅시다. 

 

Installation

$ cd ~/ros2_ws/src
$ git clone https://github.com/mgonzs13/yolov8_ros.git 
$ pip3 install -r yolov8_ros/requirements.txt
$ cd ~/ros2_ws
$ colcon build

github에 나와있는 대로 git clone을 통해서 repository를 복사해오고, pip3 install을 통해서 필요한 패키지들을 python 3 버전으로 설치해준 후 build 시켜줍니다.

 

Usage

$ ros2 launch yolov8_bringup yolov8.launch.py

이후 ros2 launch 명령어로 launch 파일을 실행시켜주면 끝!!! 이면 좋겠지만 언제나 그렇듯 오류는 항상 발생하죠.

 

아래는 제가 실행시키는 과정에서 발생한 오류들과 해결방법들입니다.

 

Errors & Solution

★ numpy의 버전이 낮습니다 

 

현재 사용하는 numpy의 버전이 패키지를 실행시키는데 필요로 하는 numpy의 버전보다 낮아서 발생하는 에러입니다. 

 

따라서 간단하게 numpy의 버전을 upgrade시켜주면 됩니다. 

$ pip install numpy --upgrade

 

★ Package 'yolov8_bringup' not found error 

 

'yolov8_bringup' 이라는 패키지를 찾을 수 없다는 에러입니다. 이 에러는 이 패키지를 사용할 때 뿐만 아니라 다른 패키지를 사용할 경우에도 많이 접할 수 있는 에러입니다. 

 

git clone을 통해서 소스 코드를 직접 다운로드하고 colcon이 build를 완료한다면 실행 파일은 사용자가 직접 설정한 디렉토리 안에 존재할 것입니다. 

 

이 패키지의 경우 ros2_ws 디렉토리 안에 실행 파일이 존재합니다. ( $ cd ~/ros2_ws/src 의 위치에서 git clone을 했기 때문) 

 

설치된 실행 파일이나 라이브러리를 사용하려면 이 위치를 사용자의 path와 library path에 경로로서 추가해줘야 합니다. 

 

colcon은 이러한 환경설정을 돕기 위해서 아래 그림과 같이 install 디렉토리 안에 bash/bat 파일을 생성해주는데, 이 파일은 필요한 모든 요소들을 사용자의 path와 library path에 추가해줍니다.

 

setup.bash 위치

 

따라서 이 에러를 해결하기 위해서는 간단하게 이 파일을 실행시켜주면 됩니다.

$ cd ros2_ws/
$ . install/setup.bash

 

★ vision_msgs 패키지가 없다

 

말 그대로 vision_msgs가 사용되는데, 이 패키지가 없어서 발생하는 에러입니다. vision_msgs은 publish 할 "detections"과 "dbg_image" topic에 detect 결과를 담기 위해 사용된 중요한 message 타입입니다.

 

이 에러를 해결하기 위해서는 아래 github 링크에서 vision_msgs 패키지를 다운받은후 build 시켜주면 됩니다.

 

https://github.com/ros-perception/vision_msgs

 

GitHub - ros-perception/vision_msgs: Algorithm-agnostic computer vision message types for ROS.

Algorithm-agnostic computer vision message types for ROS. - GitHub - ros-perception/vision_msgs: Algorithm-agnostic computer vision message types for ROS.

github.com

$ git clone https://github.com/ros-perception/vision_msgs.git
$ cd vision_msgs && git checkout foxy
$ cd ~/ros2_ws
$ colcon build --symlink-install --packages-select vision_msgs
$ source install/setup.bash

 

★ AttributeError: 'Pose2D' object has no attribute 'position' (필수)

 

위 오류들을 모두 해결하고 launch 파일을 실행시킨다면 아마 모두 위와 같은 에러 메세지가 뜨는 것을 확인할 수 있을 것입니다. 

 

해당 에러는 yolov8_node.py의 아래 코드 line 문제로,

 

오류 발생 부분

vision_msgs/Detection2D msg 파일에 없는 position 변수를 사용해서 발생한 error입니다.

 

이는 foxy 버전의 vision_msgs를 설치한 저희와 달리 yolov8_ros 패키지의 작성자는 humble 버전의 vision_msgs 패키지를 사용했기 때문인데요.

 

humble 버전의 vision_msgs의 경우 vision_msgs/Detection2D msg에 position이라는 변수가 있지만 foxy 버전의 vision_msgs에는 vision_msgs/Detection2D msg에 position이라는 변수가 없습니다. 

 

즉 지금 detection이라는 변수는 vision_msgs의 Detection2D 타입인데, position이라는 변수는 foxy 버전의 vision_msgs 안에 없는 변수이기 때문에 error가 난 것이죠.

 

http://docs.ros.org/en/lunar/api/vision_msgs/html/msg/Detection2D.html

 

vision_msgs/Detection2D Documentation

File: vision_msgs/Detection2D.msg Raw Message Definition # Defines a 2D detection result. # # This is similar to a 2D classification, but includes position information, #   allowing a classification result for a specific crop or

docs.ros.org


위 링크로 들어가보시면 foxy 버전의 vision_msgs/Detection2D msg의 구조를 확인할 수 있는데요, 간단한 그림으로 나타내면 다음과 같습니다. 

 

Detection2D msg 타입 구조vision_msgs 타입

 

실제로 Detection2D("detection"의 msg 타입) -> bbox -> center(Pose2D 타입) 안에 position이라는 변수는 없는 것을 확인하실 수 있습니다. (오른쪽 그림을 보면 x, y, theta만 존재하는 것을 확인할 수 있습니다.)

 

따라서 detection.bbox.center.position.x을 detection.bbox.center.x로 바꿔주시면 해당 error를 해결하실 수 있습니다. 이와 같이  yolov8_node.py에는 없는 변수를 사용한 코드 line이 다수 있기 때문에 나머지 부분들도 수정해 주시면 됩니다. 

 

시간이 없는 분들을 위해 아래 github에 수정된 yolov8_node.py를 올려두도록 하겠습니다~! 

 

https://github.com/goodhsm2000/yolov8_ros2/tree/main

 

GitHub - goodhsm2000/yolov8_ros2: This is a slightly modified code from the package "yolov8_ros" made by mgonzs13

This is a slightly modified code from the package "yolov8_ros" made by mgonzs13 - GitHub - goodhsm2000/yolov8_ros2: This is a slightly modified code from the package "yolov8_ros"...

github.com

 

실행시켜보기

모든 에러가 해결하고 다시 launch 파일을 실행시키면 최종적으로 아래와 같은 터미널 창이 뜹니다. subscribe 해야하는 "image_raw" topic을 기다리는 상태인 것이죠. 

 

 

$ ros2 topic list

 

위 명령어를 통해서 publish와 subscribe하는 topic을 살펴봤을 때 /image_raw, /yolo/dbg_image 그리고 /yolo/detections 모두가 잘 출력되는 것을 보면 Yolov8과 ROS2가 성공적으로 연동됐다고 볼 수 있습니다.

 

 

Reference

https://answers.ros.org/question/362922/ros2-what-is-installsetupbash-doing/ 

 

https://endland.medium.com/ros2-darknet-%EC%82%AC%EC%9A%A9%ED%95%98%EA%B8%B0-337ad8cd3d28

 

https://github.com/mgonzs13/yolov8_ros

 

https://github.com/ros-perception/vision_msgs