본문 바로가기

Nvidia Jetson

[YOLO11] Jetson Orin Nano에서 YOLO11 설치하고 돌려보기

Buongiorno! My friends, 반갑습니다.

 

오늘은 Jetson Orin Nano에 YOLO 11을 설치해서 구동하는 것을 목표로 열심히 달려보겠습니다.

 

이전 편에 설치한 Jetpack 6.1 기준으로 아무것도 설치하지 않은 상태에서 시작합니다.

https://itgear.tistory.com/27

 

[Jetson] NVMe SSD에 Jetpack 6.1 설치하기 Jetson Orin Nano Dev Kit

오늘은 Jetson Orin Nano에 Jetpack 6.1 버전을 설치한 방법을 공유해 드리려 합니다.SD 카드 없이 바로 NVMe SSD 위에다가 OS를 설치해 보도록 하겠습니다. 바로 들어가보시죠~! 1. 준비물 우선 준비물은

itgear.tistory.com

 

천천히 들어가 보죠

 

0. 도입

저는 그동안 딥러닝을 쓰면서 여러 버전의 YOLO를 거쳐왔습니다.

v2, v2-tiny, v3, v4, v4-tiny, v8까지

그래도 가장 오래 사용했던 건 v2와 v8이라서 프로젝트를 위해 v8을 설치해야지 마음먹고 있었는데요, 

아니 글쎄 11이 나왔지 뭡니까? 이번엔 특이하게도 매번 버전 앞에 붙던 v가 없어지고 YOLO11이 되었는데요

궁금한 건 참을 수 없는 만큼 새로운 버전을 시도하게 되었습니다.

 

YOLO11 🚀 신규 - Ultralytics YOLO 문서

 

YOLO11 🚀 신규

다양한 컴퓨터 비전 작업에 탁월한 정확성과 효율성을 제공하는 최첨단 물체 인식의 최신 기술인 YOLO11 을 살펴보세요.

docs.ultralytics.com

심지어 한글 사이트까지 아주 잘 되어있습니다.

 

1. 설치

사실 다크넷부터 막 빌드해야하던 시절과는 달리 설치가 매우 간편해졌습니다.

개인적으로는 설치까지 원샷인 딥러닝이 진정한 원샷 영상 처리 모델답다고 할 수 있겠습니다.

언제부터인지는 몰라도 도커까지 제공해서 정말로 간편한 활용이 가능해졌는데요, 

 

우선 이번에는 pip 설치를 목표로 진행해 보겠습니다.

아래 명령어를 통해 설치 해줍니다.

sudo apt install python3-pip
pip install ultralytics

 

위의 명령어는 pip를 설치하고, 아래는 설치된 pip로 YOLO11을 설치하는 명령어입니다.

참 쉽죠? 그러나 설치랑 실행은 별개인 법이죠

 

일단 제 기억이 맞다면, 지금 나온 최신의 PyTorch가 2.5.1 버전으로 알고 있습니다(*stable 기준).

그런데 이거 CUDA 지원이 12.4가 가장 최신 버전인데, Jetpack 6.1은 CUDA가 12.6으로 설치됩니다.

역시 가장 최신 OS는 쓰지 말라고 그랬는데..

뭐 그래도 깡 성능으로 어찌저찌 돌릴 수 있는 만큼,

이번엔 돌리는 걸 목표로 해보자구요

 

우선 vsCode나 IDLE 아무거나 편한 거로 선택하시고 아래 코드를 작성해줍니다.

 

# import YOLO
from ultralytics import YOLO

# Load YOLO11 Model
model = YOLO("yolo11s.pt")

# Run Reference
results = model("https://ultralytics.com/images/bus.jpg")

 

별 탈 없이 동작한다면 다행이지만, 아마도 버전 문제로 런타임 에러가 발생하는 경우가 많으시리라 생각합니다.

 

가장 간편한 해결책은 torch 재설치입니다.

pip3 uninstall torch torchvision torchaudio
pip3 install torch torchvision torchaudio --extra-index-url https://developer.download.nvidia.com/compute/redist/jp/v61

 

위 명령어를 통해 Jetpack 6.1에 맞는 PyTorch로 재설치해 줍니다.

그러고 다시 코드를 돌려보면 아마 실행될 것이라 생각합니다.

 

이대로 마무리하면 뭔가 아쉬우니, YOLO11 예제 코드를 공유해 드리겠습니다.

아래 코드는 간단하게 작성된 자율주행차 프로젝트 코드의 일환입니다.

 

언젠가는 블로그에 Step-by-step으로 소개해 드리고 싶은 프로젝트이지만,

도저히 시간이 여유롭지 않아 계속 공개가 밀렸던 프로젝트 중 하나입니다.

 

주석으로 설명이 되어있기는 하지만, 간단하게 추가 설명을 드리자면,

어딘가의 image_publisher에서 발행된 이미지를 받아와서 진행되는 코드입니다.

 

영상은 모빌아이(Mobileye)처럼 쉽게 말하면 블랙박스 뷰? 와 같은 Frontal View Image를 입력 이미지로 사용하고

이 영상을 YOLO에 넣어 차량을 탐지합니다.

 

또한 이 코드는 선행 차량(전방 차량)에 대한 거리 정보를 바탕으로, 전방에 차량 없음, 있지만 가깝진 않음, 가까움의 세 정도로 나누어 적절한 조향값을 생성하도록 합니다.

 

탐지된 차량 이미지에 대한 상대 거리를 판단하는 방법은 여러 석학분이 연구한 결과도 있고 훌륭한 수학적 모델도 많이 있지만

이번 프로젝트에서는 차량의 폭은 대부분 비슷하다는 부분에서 착안하여,

Bounding Box의 너비 정보를 활용하여 차량의 거리를 추론해 보도록 하겠습니다.

이러한 처리가 가능하다는 이야기는 그만큼 YOLO의 Bounding Box의 detail이 많이 올라왔다는 이야기기도 합니다.

 

참고로 아래 cls의 경우 car가 2, truck이 7이기 때문에, 탐지된 객체가 자동차거나 트럭인 경우에만 동작하는 코드라고 할 수 있겠습니다.

# using YOLO to detect vehicle, and If it detect the car, then release acc

import rclpy
from rclpy.node import Node
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
import cv2
import numpy as np
from ultralytics import YOLO

class VehiclePublisher(Node):
    def __init__(self):
        super().__init__('vehicle_publisher')

        # 퍼블리셔 생성: 'frontVeh' 토픽으로 차량 상태 발행
        self.publisher_ = self.create_publisher(String, 'frontVeh', 10)

        # YOLO11 모델 로드 (사전 훈련된 가중치 사용)
        self.model = YOLO("yolo11n.pt")  #Try using YOLO11n to increase FPS, or YOLO11m to improve accuracy.

        # cv_bridge 객체 생성
        self.bridge = CvBridge()

        # 'camera_frame' 토픽에서 이미지 구독
        self.subscription = self.create_subscription(
            Image,
            'video_frames',
            self.image_callback,
            10
        )
        self.subscription  # 방금 구독한 내용을 기록하기 위한 변수
        
        # Init을 마쳤다고 알림림
        self.get_logger().info('Vehicle Publisher Node Initialized')

    def image_callback(self, msg): #이미지가 들어왔을 때 호출되는 callback 함수
        # ROS Image 메시지를 cv2형식의의 이미지로 변환
        frame = self.bridge.imgmsg_to_cv2(msg, "bgr8")

        # 프레임 크기 얻기
        height, width, _ = frame.shape

        # 차선 영역(ROI) 설정: 차선 밖 좌우 영역 제외, 하단 1/3은 후드라서 제외, 상단 1/3은 하늘이어서 제외
        roi_top = 512
        roi_bottom = 690
        roi_left = 920
        roi_right = 1000

        # ROI 적용하여 관심 영역 자르기
        roi = frame[roi_top:roi_bottom, roi_left:roi_right]

        # YOLO11로 객체 탐지
        results = self.model.predict(roi, conf=0.4) # conf(신뢰도) 0.4 이상인 객체만 results에 반환할 것
        
        vehicle_detected = False  # 객체 탐지 여부 플래그
        
        for result in results:
            boxes = result.boxes
            # result.save(f"yolo_{self.get_clock().now().to_msg().sec}.jpg")
            for box in boxes:
                x1, y1, x2, y2 = box.xyxy[0]
                cls = int(box.cls[0])
                
                if cls == 2 or cls == 7: # car or truck
                    width = y2-y1
                    if width < 20:
                        self.publisher_.publish(String(data="None"))
                        self.get_logger().info('None')
                    elif width < 35:
                        self.publisher_.publish(String(data="Neutral"))
                        self.get_logger().info('Neutral')
                    else:
                        self.publisher_.publish(String(data="Brake")) 
                        self.get_logger().warn('Brake')
                        
        # 객체가 감지되지 않았을 때
        if not vehicle_detected:
            self.publisher_.publish(String(data="None"))     
            self.get_logger().info('None')  

def main(args=None):
    rclpy.init(args=args)
    vehicle_publisher = VehiclePublisher()

    try:
        rclpy.spin(vehicle_publisher)
    except KeyboardInterrupt:
        vehicle_publisher.get_logger().info('Shutting down Vehicle Publisher')
    finally:
        vehicle_publisher.destroy_node()
        rclpy.shutdown()

if __name__ == '__main__':
    main()