Глава 7. Цветовая сегментация

1. Цель занятия и обзор плана

На этом занятии мы возьмём кадр, который уже умеем получать от видеокамеры и обрабатывать в ROS, и извлечём из него полезную информацию для управления роботом. Инструмент для этого — цветовая сегментация. Также мы познакомимся с некоторыми базовыми понятиями классического компьютерного зрения и освоим удобный механизм — сервер параметров ROS.

После завершения занятия вы сможете:

  • преобразовывать изображение между цветовыми пространствами (RGB, HSV);

  • создавать бинарные маски для выделения объектов заданного цвета;

  • применять морфологические операции для очистки маски от шумов;

  • находить и фильтровать контуры объектов;

  • рассчитывать азимут на объект по его положению в кадре;

  • настраивать параметры сегментации «на лету» через сервер параметров ROS.

1.1. Обзор плана занятия

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

  2. Цветовые пространства: RGB, HSV и другие.

  3. Бинарная маска: фильтрация по цвету.

  4. Сервер параметров ROS: настройка порогов «на лету».

  5. Морфологические операции: очистка маски от шумов.

  6. Выделение контуров и расчёт координат.

  7. Расчёт азимута на объект.

2. Теоретический материал

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

На прошлом занятии мы научились получать изображение с камеры, рисовать на нём прямоугольники и текст. Но рисовали мы их вручную — в заранее заданных координатах. А нам нужно, чтобы катамаран сам находил объекты на изображении и реагировал на них.

Представьте: вы смотрите на экран и видите красный буй на фоне синей воды. Для вас выделить буй — тривиальная задача. Но компьютер видит просто массив чисел (помните — изображение это NumPy-массив). Ему нужен чёткий алгоритм: «возьми каждый пиксель, проверь, похож ли он на красный, если да — оставь, если нет — выкинь». Именно это и делает цветовая сегментация.

Цветовая сегментация — это процесс разделения изображения на области на основе цветовых характеристик пикселей. На выходе мы получаем чёрно-белое изображение (бинарную маску), где белые пиксели — это найденные объекты нужного цвета, а чёрные — всё остальное.

Классическое компьютерное зрение обладает важными преимуществами:

  • предсказуемость — мы точно знаем, как работает алгоритм;

  • не требует обучающих данных — не нужна нейросеть, датасет, GPU;

  • вычислительная эффективность — работает даже на слабых процессорах.

Но у него есть и существенные ограничения. Цветовая сегментация хрупка: при смене освещения (восход, закат, облака) цвета «плывут», и алгоритм перестаёт работать. Мимо проходит человек в жёлтой футболке — и алгоритм принимает его за буй. В симуляторе всё работает отлично, но в реальной жизни качество оставляет желать лучшего. Именно поэтому в последующих уроках мы дополним классические методы нейросетями. Но как первое приближение — почему бы и нет, вполне себе работает.

2.2. Подготовка

Склонируйте репозиторий занятия, если ещё не сделали:

$ git clone http://sdb.smtu.ru/gitlab/marinerobotics/lesson_07.git

Запустите симулятор, выберите сцену с маркерами и переведите катамаран в угол, где нижняя камера видит несколько маркеров сразу. Так мы сможем работать с видеопотоком, содержащим разноцветные объекты.

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

RGB (BGR в OpenCV)

Вы наверняка знаете, что чаще всего изображения в компьютере представлены в виде суммы трёх цветов: красного (Red), зелёного (Green) и синего (Blue). Каждый пиксель — это три числа, описывающие интенсивность каждого канала. Глубина цвета — 8 бит на канал, то есть каждое значение лежит в диапазоне от 0 (полное отсутствие) до 255 (максимальная яркость).

Напомним: в OpenCV порядок каналов — BGR (синий, зелёный, красный), а не RGB!

Но как узнать, какие числа соответствуют нужному цвету? Можно ли просто задать «красный = (255, 0, 0)»? К сожалению, нет. Реальный красный треугольник-маркер в симуляторе — это не чистый красный. Если взять инструмент «пипетка» в любом графическом редакторе (сделайте скриншот кадра и откройте в редакторе) и ткнуть в красный маркер, вы увидите что-то вроде: R=143, G=6, B=40. Не чисто красный, правда?

Более того, этот цвет на разных маркерах будет немножко разным. А при изменении освещённости — разным ещё сильнее. Поэтому мы не можем задать один конкретный цвет — мы должны задавать диапазон: нижнюю и верхнюю границу для каждого канала.

HSV

В пространстве HSV (Hue — оттенок, Saturation — насыщенность, Value — яркость) информация о цвете отделена от яркости. Это делает HSV значительно более удобным для сегментации.

Почему? Представьте, что вы выделяете красный буй. В RGB при изменении освещения меняются все три компонента одновременно — красный, зелёный и синий. А в HSV при изменении освещения меняется в основном компонента V (яркость), а оттенок H остаётся стабильным. Это значит, что один и тот же набор порогов по H будет работать и при ярком солнце, и в тени.

Преобразование изображения:

hsv = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV)

На практике для задач сегментации чаще используют именно HSV, а не RGB. Мы начнём с RGB (он проще для понимания), а потом перейдём на HSV.

Совет: существуют и другие цветовые пространства. Например, YUV может быть удобнее при выделении синих объектов на синем фоне. Для выравнивания яркости часто используют пространство LAB: компонента L (яркость) нормализуется, что улучшает стабильность сегментации в различных условиях освещения.

2.4. Бинарная маска

Бинарная маска создаётся при помощи функции cv2.inRange(). Она проверяет каждый пиксель изображения: попадает ли он в заданный диапазон значений? Если да — белый (255), если нет — чёрный (0).

import cv2
import numpy as np

# Нижняя и верхняя границы по каналам (B, G, R)
lower_gate = np.array([0, 0, 100])    # мало синего, мало зелёного, много красного
upper_gate = np.array([50, 50, 255])   # верхние границы

# Создаём маску
mask = cv2.inRange(frame, lower_gate, upper_gate)

На выходе mask — чёрно-белое изображение того же размера, что и исходный кадр. Белые области — это пиксели, попавшие в диапазон (наши «красные» объекты), чёрные — всё остальное.

Попробуйте: запустите пример step_0 из репозитория. Откройте RQT и расположите рядом два изображения: оригинальное (с камеры) и бинарную маску. Вы увидите, что красные маркеры выделены белым. Но также заметите «мусор» — случайные белые пятна, которые не являются маркерами. Это нормально, позже мы научимся с этим бороться.

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

Менять числа в коде и перезапускать ноду каждый раз — неудобно. Хочется иметь возможность подбирать пороги «на лету», двигая ползунки и наблюдая результат в реальном времени.

Для этого в ROS существует сервер параметров. Идея такая: вместо того чтобы жёстко прописывать числа в коде, мы объявляем их как параметры ноды, которые можно менять извне.

В коде это выглядит так:

# В конструкторе ноды объявляем параметры с описателями (дескрипторами)
from rcl_interfaces.msg import ParameterDescriptor, IntegerRange

# Простой параметр — просто значение по умолчанию
self.declare_parameter('min_area', 100)

# Параметр с описателем — имеет диапазон и шаг
self.declare_parameter('lower_r', 100,
    ParameterDescriptor(
        integer_range=[IntegerRange(from_value=0, to_value=255, step=1)]
    )
)
self.declare_parameter('upper_r', 255,
    ParameterDescriptor(
        integer_range=[IntegerRange(from_value=0, to_value=255, step=1)]
    )
)

Описатель (ParameterDescriptor) с диапазоном (IntegerRange) даёт системе знать, что параметр — целое число от 0 до 255 с шагом 1. Благодаря этому в графическом интерфейсе появится удобный ползунок.

Для чтения параметров в обработчике изображения:

lower_r = self.get_parameter('lower_r').value
upper_r = self.get_parameter('upper_r').value

Чтобы настраивать параметры через GUI, откройте в RQT: PluginsConfigurationDynamic Reconfigure. Здесь вы увидите все объявленные параметры вашей ноды с ползунками.

Цикл работы такой:

  1. Запускаете ноду и RQT.

  2. Двигаете ползунки, наблюдая бинарную маску в реальном времени.

  3. Подбираете оптимальные пороги для нужного цвета.

  4. Сохраняете параметры в YAML-файл (кнопка в Dynamic Reconfigure).

  5. Загружаете YAML через launch-файл при следующем запуске.

Это правильный подход к разработке: отделять параметры от логики. Параметры хранятся отдельно, их может менять любой пользователь (даже не программист), а код остаётся неизменным.

2.6. Морфологические операции

Итак, мы получили бинарную маску. Но на ней есть «мусор» — мелкие белые точки, которые не являются нашими объектами. Как от них избавиться?

Один из способов — морфологические операции. Не пугайтесь названия, на практике всё просто.

Ядро (kernel)

Ядро — это небольшая матрица (например, 5×5 пикселей), которая используется при обработке изображения. Для каждого пикселя результирующего изображения алгоритм смотрит на область вокруг него (определяемую ядром) в исходном изображении. Ядро может быть прямоугольным, эллиптическим или крестообразным.

kernel = cv2.getStructuringElement(cv2.MORPH_ELLIPSE, (5, 5))

Эрозия (Erosion) и Дилатация (Dilation)

Две базовые операции:

  • Эрозия (утоньшение): пиксель остаётся белым, только если все пиксели в области ядра — белые. Иначе он становится чёрным. Результат: белые области уменьшаются, мелкие белые точки исчезают полностью.

  • Дилатация (утолщение): пиксель становится белым, если хотя бы один пиксель в области ядра — белый. Результат: белые области увеличиваются, мелкие чёрные «дырки» внутри объектов заполняются.

Opening и Closing

На практике чаще используют комбинированные операции:

  • Opening (открытие) = эрозия + дилатация. Сначала утоньшаем — мелкие точки-шумы исчезают. Потом утолщаем обратно — крупные объекты восстанавливаются до исходного размера. Итог: шум удалён, объекты на месте.

  • Closing (закрытие) = дилатация + эрозия. Наоборот: сначала утолщаем — мелкие чёрные дырки внутри объектов заполняются. Потом утоньшаем обратно. Итог: объекты стали «цельными».

Представьте букву «J» с мелкими точками вокруг неё. После opening: точки исчезли, буква стала чуть тоньше, потом восстановилась. Точки восстановить уже невозможно — они исчезли полностью при эрозии.

kernel = cv2.getStructuringElement(cv2.MORPH_ELLIPSE, (5, 5))

# Удаляем мелкий шум (opening)
mask = cv2.morphologyEx(mask, cv2.MORPH_OPEN, kernel)

# Заполняем дырки внутри объектов (closing)
mask = cv2.morphologyEx(mask, cv2.MORPH_CLOSE, kernel)

Всего три строчки кода — а мусор ушёл. Запустите пример с морфологическими операциями и сравните результат с предыдущим.

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

Отлично, мы получили чистую бинарную маску: белые области — наши объекты, чёрное — фон. Но нам нужны не просто белые пиксели, а сущности: объекты с координатами, размером, центром. Нужно превратить набор пикселей в данные, с которыми можно работать.

Для этого используется выделение контуров:

contours, _ = cv2.findContours(mask, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)

findContours находит границы связных белых областей и возвращает их в виде массива контуров. Каждый контур — это массив точек, описывающих границу одной области.

Для каждого контура можно получить:

# Площадь контура (в пикселях²)
area = cv2.contourArea(contour)

# Описывающий прямоугольник (x, y — верхний левый угол, w, h — ширина и высота)
x, y, w, h = cv2.boundingRect(contour)

# Центр контура
center_x = x + w // 2
center_y = y + h // 2

# Нарисовать контур на изображении (зелёным, толщина 2)
cv2.drawContours(frame, [contour], 0, (0, 255, 0), 2)

2.8. Фильтрация контуров

На бинарной маске могут остаться мелкие области даже после морфологических операций. Поэтому контуры дополнительно фильтруют:

# Сортируем контуры по площади (от большего к меньшему)
contours = sorted(contours, key=cv2.contourArea, reverse=True)

min_area = self.get_parameter('min_area').value

for contour in contours:
    area = cv2.contourArea(contour)
    if area < min_area:
        continue  # слишком маленький — пропускаем

    x, y, w, h = cv2.boundingRect(contour)
    center_x = x + w // 2
    center_y = y + h // 2

    # Рисуем крестик в центре контура
    cv2.drawMarker(frame, (center_x, center_y), (0, 0, 255),
                   cv2.MARKER_CROSS, 20, 2)

Параметр min_area вынесен в сервер параметров — его можно менять через Dynamic Reconfigure. Увеличиваете порог — мелкие контуры пропадают. Уменьшаете — появляются.

Пусть вас не смущает, что результат — «всего лишь крестик на экране». Этот крестик нарисован в точных координатах, вычисленных программой. А значит, мы знаем цифровое положение объекта в кадре — точно так же, как знали координаты черепахи в первом занятии. И дальше можем наводиться на него, удерживать в центре кадра, рассчитывать расстояние.

2.9. Расчёт азимута на объект

Зная горизонтальный угол обзора камеры (FOV — Field of View) и положение центра объекта в кадре, можно рассчитать азимут — угол отклонения объекта от оптической оси камеры.

Для камер с малым углом обзора (менее ~90°) можно использовать линейную аппроксимацию:

# center_x — координата центра объекта в пикселях
# width — ширина кадра в пикселях
# fov — горизонтальный угол обзора камеры в градусах

azimuth = (center_x - width / 2) / width * fov

Если объект в центре кадра — азимут равен нулю. Если левее центра — азимут отрицательный. Если правее — положительный.

Для камер с большим углом обзора линейная аппроксимация даёт погрешность, и используется точная тригонометрическая формула:

azimuth = np.rad2deg(
    np.arctan(
        (center_x - width / 2) * np.tan(np.deg2rad(fov / 2)) / (width / 2)
    )
)

В нашем симуляторе угол обзора — 90°, так что можно использовать как линейную формулу, так и точную. На практике разница невелика, но для точных задач лучше использовать тригонометрическую формулу.

2.10. Оценка дистанции до сферического объекта

Если известен реальный размер объекта (например, диаметр буя), можно оценить дистанцию до него по его видимому размеру в кадре. Чем дальше объект — тем меньше он выглядит:

distance = a / angular_size + b

Параметры a и b определяются экспериментально: замерьте видимый размер объекта на нескольких известных дистанциях и подберите коэффициенты. Это грубая оценка, но для навигации бывает достаточно.

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

  1. По изображению нижней камеры определяйте, фигуру какого цвета вы видите (жёлтую, красную или зелёную).

  2. Выводите в лог: цвет фигуры, её площадь, положение её центра.

  3. Нарисуйте описывающий прямоугольник и крестик в центре найденного объекта.

  4. Задача со звёздочкой: попробуйте в автоматическом режиме пройти через ворота из буёв, используя цветовую сегментацию и регулятор курса.

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

Документация OpenCV по цветовым пространствам

https://docs.opencv.org/4.x/df/d9d/tutorial_py_colorspaces.html

https://docs.opencv.org/4.x/df/d9d/tutorial_py_colorspaces.html

Документация OpenCV по контурам

https://docs.opencv.org/4.x/d4/d73/tutorial_py_contours_begin.html

https://docs.opencv.org/4.x/d4/d73/tutorial_py_contours_begin.html

Документация 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

Документация ROS2: параметры нод

https://docs.ros.org/en/jazzy/Concepts/Basic/About-Parameters.html

https://docs.ros.org/en/jazzy/Concepts/Basic/About-Parameters.html