Основы программировния морских роботов

Цветовая сегментация

logo
smtu logo

План занятия

  • Цель занятия:

    • получить из изображения камеры данные для обратной связи

  • Мы изучим:

    • Зачем нужна цветовая сегментация

    • Основные понятия классического компьютерного зрения

  • Дополнительные технологии:

    • Сервер параметров ROS

Подготовка

Склонировать репозиторий

Запуск ПО

  • Обновить симулятор: https://sdb.smtu.ru/nextcloud/s/simulator

  • Запустить симулятор

    • Выбрать сцену "Сбор датасета"

  • Запустить RQT

    • Вывести изображение с нижней камеры и навестись на маркеры

preparings

Цветовая сегментация

binary mask

Пример: step_0

ros2 launch lesson_07 main.launch.py lesson_num:=0

cv2.inRange

    def image_processing_callback(self, msg: Image) -> None:
        cv_image = self.bridge.imgmsg_to_cv2(msg)
        # Создание бинарной маски изображения
        mask = cv2.inRange(cv_image, np.array([0, 0, 0]), np.array([255, 50, 50]))

        result =  self.bridge.cv2_to_compressed_imgmsg(mask)
        self.image_publisher.publish(result)

Маска в пространстве RGB

  • Нижняя граница: [0, 0, 0]

  • Верхняя граница: [255, 50, 50]

rgb

Получение информации через графический редактор

  • Сделать скриншот

  • Вставить в графический редактор

    • pinta, gimp и т.д.

  • Воспользоваться инструментом "пипетка"

pinta

Сервер параметров ROS

  • Правильно отделять настраиваемые параметры от кода и хранить их отдельно

  • Нужна возможность менять эти параметры в реальном времени

  • Нужен стандарт для хранения этих настроек

Объявление параметров

from rcl_interfaces.msg import ParameterDescriptor, IntegerRange
#...
self.declare_parameter('minimum_area', 300)

range = IntegerRange(from_value=0, to_value=255, step=1)
descriptor = ParameterDescriptor(integer_range=[range])
self.declare_parameter('lower_limit.r', 0, descriptor)

Просмотр и редактирование параметров

  • rqt

    • Plugins → Configuration → Dynamic Reconfigure

  • Можно работать и через консоль (см. доп. материалы)

parameter server

Пример: step_1

ros2 launch lesson_07 main.launch.py lesson_num:=1

Сохранение конфгурации в yaml

higher_limit.b: 90
higher_limit.g: 255
higher_limit.r: 255
lower_limit.b: 0
lower_limit.g: 116
lower_limit.r: 115
minimum_area: 300
start_type_description_service: true
use_sim_time: false

Загрузка конфигурации из yaml-файла (launch)

def config_file(pkg, filename):
    path = os.path.join(get_package_share_directory(pkg), 'config', filename).split('/')
    for i in range(path.index("share"), path.index("install") - 1, -1):
        path.pop(i)
    path.insert(i, "src")
    return "/".join(path)

#...

parameters=[
    config_file("lesson_07", 'yellow_mask.yaml'),
    ]

Улучшения качества изображения

Демонстрация проблемы

noise
noise cleaned
ros2 launch lesson_07 main.launch.py lesson_num:=2

На уровне OpenCV

    kernel = cv2.getStructuringElement(cv2.MORPH_ELLIPSE, (5,5))
    mask = cv2.morphologyEx(mask, cv2.MORPH_OPEN, kernel)
    mask = cv2.morphologyEx(mask, cv2.MORPH_CLOSE, kernel)

Ядро (kernel)

  • Ядро скользит по изображению (см. рисунок)

  • Пиксель в результирующем изображении зависит от

    • пикселей исходного изображения

    • пикселей ядра

    • операции над пикселями исходного изображения

kernel

Варианты ядер

# Rectangular Kernel
>>> cv.getStructuringElement(cv.MORPH_RECT,(5,5))
array([[1, 1, 1, 1, 1],
       [1, 1, 1, 1, 1],
       [1, 1, 1, 1, 1],
       [1, 1, 1, 1, 1],
       [1, 1, 1, 1, 1]], dtype=uint8)

# Elliptical Kernel
>>> cv.getStructuringElement(cv.MORPH_ELLIPSE,(5,5))
array([[0, 0, 1, 0, 0],
       [1, 1, 1, 1, 1],
       [1, 1, 1, 1, 1],
       [1, 1, 1, 1, 1],
       [0, 0, 1, 0, 0]], dtype=uint8)

# Cross-shaped Kernel
>>> cv.getStructuringElement(cv.MORPH_CROSS,(5,5))
array([[0, 0, 1, 0, 0],
       [0, 0, 1, 0, 0],
       [1, 1, 1, 1, 1],
       [0, 0, 1, 0, 0],
       [0, 0, 1, 0, 0]], dtype=uint8)

# Diamond-shaped Kernel
>>> cv.getStructuringElement(cv.MORPH_DIAMOND,(5,5))
array([[0, 0, 1, 0, 0],
       [0, 1, 1, 1, 0],
       [1, 1, 1, 1, 1],
       [0, 1, 1, 1, 0],
       [0, 0, 1, 0, 0]], dtype=uint8)

Opening = Erosion + Dilation

Исходное:

j

Errosion, dilation

erosion
dilation

Openging

opening

Closing = Dilation + Erosion

closing

Выделение контуров

Постановка задачи

  • Нужно отсеять оставшиеся мелкие контуры

  • Нужно посчитать площадь объекта

  • Нужно определить границы объекта

    ros2 launch lesson_07 main.launch.py lesson_num:=3
contour

Исходный код

contours, _ = cv2.findContours(mask, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
sorted_contours = sorted(contours, key=cv2.contourArea, reverse=True)
biggest_contour = sorted_contours[0]

M = cv2.moments(biggest_contour)
center = (int(M["m10"] / M["m00"]), int(M["m01"] / M["m00"]))

area = cv2.contourArea(biggest_contour)

cv2.drawMarker(mask, center, marker_color, markerType=cv2.MARKER_CROSS,
    markerSize=10, thickness=2, line_type=cv2.LINE_AA)

Дополнительные материалы

Цветовые пространства

  • cv2.cvtColor(frame, cv2.COLOR_URCOLORSPACE) # преобразование изображения в другой формат

  • RGB (красный, зелёный, синий)

  • HSV (оттенок, насыщенность, яркость)

    • HSV удобнее для сегментации, потому что он отделяет информацию о цвете (оттенок) от яркости и насыщенности, что позволяет легче выделять объекты при изменении освещённости

Иные цветовые пространства

  • Существуют и другие цветовые пространства, которые могут быть более удобны в определённых задачах, например, YUV при выделение синих объектов на синем фоне

  • Для выравнивания яркости часто используют LAB

  • Для типографии часто используют CMYK

DOI:10.1007/s13319-019-0229-8

hsv example

Сегодня я многое понял

  • Основы классических алгоритмов компьютерного зрения

  • Цветовые пространства

  • Сервер параметров ROS

common:KyleBroflovski

Дополнительные материалы

Морфологические операции в OpenCV https://docs.opencv.org/4.x/d9/d61/tutorial_py_morphological_ops.html

https://docs.opencv.org/4.x/d9/d61/tutorial_py_morphological_ops.html

Сервер параметров

https://docs.ros.org/en/jazzy/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Parameters/Understanding-ROS2-Parameters.html

KyleBroflovski
 https://docs.ros.org/en/jazzy/Tutorials/Beginner-CLI-Tools/Understanding-ROS2-Parameters/Understanding-ROS2-Parameters.html

Домашнее задание

  • По изображению нижней камеры катамарана определить фигуру какого цвета вы видите

  • Вывести в лог:

    • Цвет фигуры

    • Площадь фигуры

    • Её положение по центру

  • Задание со звёздочкой:

    • Попробуйте выделить по цветам ворота из двух буёв и попробуйте пройти через их центр в автоматическом режиме