Глава 6. Работа с видеокамерой
1. Цель занятия и обзор плана
На этом занятии мы научимся работать с видеокамерами — от низкоуровневого доступа через Video4Linux до получения и обработки изображений средствами OpenCV и интеграции камеры в ROS-систему катамарана.
После завершения занятия вы сможете:
-
определять подключённые камеры и управлять их параметрами через
v4l2-ctl; -
понимать форматы видеопотока (MJPEG, YUYV) и осознанно выбирать нужный;
-
получать видеопоток с камеры в Python с помощью OpenCV;
-
понимать, что изображение — это массив чисел, и работать с ним как с данными;
-
наносить на изображение текст и графические примитивы;
-
запускать ROS-ноду камеры и просматривать изображение в RQT;
-
настраивать параметры камеры через YAML-файл и launch-файл;
-
выполнять калибровку камеры для устранения дисторсии.
1.1. Обзор плана занятия
-
Зачем нужна камера — мотивация.
-
Подготовка окружения — установка необходимых пакетов.
-
Video4Linux (V4L2) — работа с камерами на уровне Linux.
-
OpenCV — получение и модификация изображений в Python.
-
ROS и камера — нода
usb_cam, параметры, работа с изображениями в ROS. -
Калибровка камеры — зачем нужна и как выполнить.
2. Теоретический материал
2.1. Зачем нам нужна камера
В предыдущих главах мы управляли катамараном — двигались прямо заданное число секунд, поворачивали, снова двигались. Но мы уже поняли, что такой подход хрупок: любое внешнее вмешательство (ветер, течение, неточность моторов) разрушит нашу систему. Простое движение по таймерам не работает. Пройти задание соревнований «по точкам» не выйдет.
При этом, пользуясь обратной связью от видеоизображения — глядя глазами катамарана — вы легко пройдёте миссию: пройдёте между буями, припаркуетесь в нужный гараж. Для вас это не проблема. Осталось научить компьютер так же управляться с видеоизображением, как и вы. Конечно, так же профессионально он не сможет, но кое-чему мы его научим.
Таким образом, мы замыкаем обратную связь при помощи такого сенсора, как видеокамера. Сегодняшнее занятие — техническая подготовка: мы разберёмся, как получить изображение, как его обработать, как передать в ROS. А уже на следующих занятиях будем извлекать из изображения полезную информацию для управления.
2.2. Подготовка окружения
Установите необходимые пакеты:
$ sudo apt install v4l-utils # утилиты для работы с камерами
$ sudo apt install qv4l2 # графическая утилита V4L2
$ sudo apt install python3-opencv # библиотека OpenCV
$ sudo apt install *jazzy-compressed* # ROS: работа со сжатыми изображениями
$ sudo apt install ros-jazzy-usb-cam # нода для USB-камер
$ sudo apt install ros-jazzy-camera-calibration # калибровка камеры
Склонируйте репозиторий занятия:
$ git clone http://sdb.smtu.ru/gitlab/marinerobotics/lesson_06.git
В этом репозитории находятся примеры кода и шаблон для домашнего задания.
3. Video4Linux (V4L)
3.1. Камера — это файл
V4L2 (Video4Linux 2) — это API ядра Linux для работы с видеоустройствами. V4L — общая система для работы с аудио и видео, а V4L2 — её актуальная, вторая версия. Здесь работает знакомый нам принцип: в Linux почти всё — файл. В том числе видеокамера. С точки зрения системы камера — это файл /dev/video*, к которому можно обращаться.
Основные утилиты для работы с камерами:
-
v4l2-ctl— командная строка для получения и настройки параметров камеры (яркость, контраст, форматы, буферы и т.д.); -
qv4l2— то же самое, но с графическим интерфейсом.
3.2. Просмотр подключённых камер
$ v4l2-ctl --list-devices
Команда покажет все доступные камеры и соответствующие им устройства /dev/video*. Вот пример вывода на ноутбуке:
Integrated IR Camera: Integrate (usb-0000:00:14.0-5):
/dev/video0
/dev/video1
/dev/media0
Integrated Camera: Integrated C (usb-0000:00:14.0-8):
/dev/video2
/dev/video3
/dev/media1
Здесь видно две камеры. Первая — инфракрасная (IR Camera), используемая для распознавания лица (например, Windows Hello). Вторая — обычная встроенная веб-камера. У каждой камеры есть несколько связанных устройств: одно для захвата видео, другие — для метаданных и управления.
Попробуйте выполнить эту команду на своём компьютере. Если у вас ноутбук, вы, скорее всего, увидите похожую картину. Если подключена внешняя USB-камера, она тоже появится в списке. Можно также быстро посмотреть список устройств командой ls /dev/video*.
3.3. Просмотр параметров камеры
$ v4l2-ctl -d /dev/video2 --all
Эта команда выведет подробную информацию: имя драйвера, тип карты (название камеры), текущее разрешение, формат пикселей, частоту кадров, а также пользовательские параметры.
Вот фрагмент типичного вывода (секция «User Controls»):
User Controls
brightness 0x00980900 (int) : min=0 max=255 step=1 default=128 value=30
contrast 0x00980901 (int) : min=0 max=255 step=1 default=32 value=0
saturation 0x00980902 (int) : min=0 max=100 step=1 default=64 value=0
hue 0x00980903 (int) : min=-180 max=180 step=1 default=0 value=-180
white_balance_automatic 0x0098090c (bool) : default=1 value=1
white_balance_temperature 0x0098091a (int) : min=2800 max=6500 step=10 default=4600 value=4600
Camera Controls
auto_exposure 0x009a0901 (menu) : min=0 max=3 default=3 value=1 (Manual Mode)
exposure_time_absolute 0x009a0902 (int) : min=2 max=1250 step=1 default=156 value=2
Информации здесь много, не вся она нужна прямо сейчас. Но обратите внимание: у каждого параметра есть минимум, максимум, шаг и значение по умолчанию. Это позволяет точно контролировать камеру из командной строки или из программы.
3.4. Форматы и разрешения
$ v4l2-ctl -d /dev/video2 --list-formats-ext
Видеокамеры — довольно сложные устройства. Современные USB-камеры зачастую умеют выдавать видео в разных форматах. Вот типичный вывод:
[0]: 'MJPG' (Motion-JPEG, compressed)
Size: Discrete 1280x720
Interval: Discrete 0.033s (30.000 fps)
Size: Discrete 640x480
Interval: Discrete 0.033s (30.000 fps)
...
[1]: 'YUYV' (YUYV 4:2:2)
Size: Discrete 1280x720
Interval: Discrete 0.100s (10.000 fps)
Size: Discrete 640x480
Interval: Discrete 0.033s (30.000 fps)
...
Здесь мы видим два формата:
-
MJPEG (Motion-JPEG) — каждый кадр представляет собой фактически JPEG-изображение, сжатое сразу на камере. Это значительно уменьшает объём передаваемых данных. Обратите внимание: в формате MJPEG камера выдаёт 1280×720 при 30 fps, а в YUYV — только 10 fps при том же разрешении. Дело в том, что несжатый видеопоток YUYV при разрешении 1280×720 создаёт огромный трафик (~27 МБ/с), и пропускная способность USB просто не позволяет передавать больше 10 кадров в секунду.
-
YUYV (4:2:2) — несжатый формат, в котором каждые два пикселя делят одну пару цветовых значений. Качество выше (нет артефактов JPEG-сжатия), но объём данных значительно больше.
Для работы с катамараном по беспроводному каналу связи (Wi-Fi) формат MJPEG — однозначный выбор. Меньше трафика — стабильнее связь, меньше задержка.
3.5. Изменение параметров
$ v4l2-ctl -d /dev/video0 --get-ctrl=brightness
brightness: 128
$ v4l2-ctl -d /dev/video0 --set-ctrl=brightness=30
$ v4l2-ctl -d /dev/video0 --get-ctrl=brightness
brightness: 30
Основные параметры камеры, которые чаще всего приходится настраивать:
-
brightness — яркость изображения;
-
contrast — контрастность;
-
saturation — насыщенность цвета;
-
hue — оттенок;
-
exposure_time_absolute — время экспозиции (при ручном режиме);
-
auto_exposure — режим экспозиции (1 = ручной, 3 = автоматический);
-
white_balance_automatic — автоматический баланс белого (0 = выключен, 1 = включён);
-
white_balance_temperature — цветовая температура баланса белого (при ручном режиме).
Важно: когда мы будем работать с машинным зрением, эти параметры окажутся критически важны. Представьте ситуацию: вы настроили алгоритм на определённые цвета (скажем, детектируете красный буй по оттенку). Работает идеально. А потом камера внезапно решает поменять баланс белого, потому что облако закрыло солнце — и красный становится оранжевым. Ваш алгоритм мгновенно ломается.
Поэтому для задач машинного зрения автоматический баланс белого и автоматическую экспозицию часто приходится отключать и выставлять фиксированные значения. Да, при изменении освещения картинка будет выглядеть «хуже» для глаза, зато цвета останутся стабильными — а для алгоритма это важнее.
# Отключить автоматический баланс белого и зафиксировать значение
$ v4l2-ctl -d /dev/video0 --set-ctrl=white_balance_automatic=0
$ v4l2-ctl -d /dev/video0 --set-ctrl=white_balance_temperature=4600
# Переключить экспозицию в ручной режим
$ v4l2-ctl -d /dev/video0 --set-ctrl=auto_exposure=1
$ v4l2-ctl -d /dev/video0 --set-ctrl=exposure_time_absolute=156
3.6. Графический интерфейс qv4l2
Всё то, что описано выше в консоли, можно делать и в графическом интерфейсе qv4l2. Запустите его:
$ qv4l2
Выберите нужную камеру, настройте параметры, попробуйте проиграть видео. Правда, функция воспроизведения в qv4l2 иногда работает не идеально — уж не знаю почему, но это факт. В качестве альтернативы для просмотра видео можно использовать VLC — там тоже можно выбрать устройство /dev/video* и посмотреть изображение с камеры.
Практическое задание:
-
Выведите список подключённых камер командой
v4l2-ctl --list-devices. -
Просмотрите параметры одной из камер через
v4l2-ctl -d /dev/videoX --all. -
Посмотрите доступные форматы и разрешения через
--list-formats-ext. -
Попробуйте изменить яркость и вернуть обратно.
-
Откройте
qv4l2и повторите то же самое через графический интерфейс.
4. OpenCV
4.1. Что такое OpenCV
OpenCV (Open Source Computer Vision Library) — библиотека алгоритмов компьютерного зрения и обработки изображений. Разработана компанией Intel, причём существенную роль в её разработке сыграли наши соотечественники (компания Itseez, Нижний Новгород). На сегодняшний день — де-факто стандарт в области «классического» компьютерного зрения.
Что значит «классическое» компьютерное зрение? Это применение различных математических алгоритмов напрямую к изображению — детерминированных, понятных. Мы выполняем математические операции с кадром и получаем нужный результат. Мы точно знаем, что происходит на каждом шаге, и можем предсказать результат.
В противовес этому «неклассическое» зрение — это нейросети, к которым мы обратимся в последующих занятиях. Нейросети зачастую показывают значительно лучший результат, но они сложнее в подготовке, требовательнее к вычислительным ресурсам, и мы не до конца понимаем, как конкретно внутри проходит обработка. А сегодня и на следующем занятии мы поработаем именно с классическими методами.
4.2. Изображение — это массив чисел
Прежде чем работать с изображениями, важно понять, что они собой представляют в памяти компьютера. Изображение в OpenCV — это обычный NumPy-массив (тип numpy.ndarray) с тремя измерениями:
# frame.shape вернёт, например, (480, 640, 3)
# 480 — высота (количество строк пикселей)
# 640 — ширина (количество столбцов)
# 3 — количество цветовых каналов (B, G, R)
Каждый пиксель — это три числа от 0 до 255, определяющие интенсивность синего (Blue), зелёного (Green) и красного (Red) каналов. Обратите внимание на порядок: BGR, а не RGB! Это историческая особенность OpenCV, которая часто становится источником ошибок. Если вы когда-нибудь увидите, что красные объекты стали синими (или наоборот) — скорее всего, где-то перепутан порядок каналов.
import cv2
import numpy as np
# Создать чёрное изображение 480x640 с 3 каналами
black = np.zeros((480, 640, 3), dtype=np.uint8)
# Создать красное изображение (помним: BGR!)
red = np.zeros((480, 640, 3), dtype=np.uint8)
red[:, :, 2] = 255 # Красный канал — третий (индекс 2)
# Получить значение пикселя в точке (100, 200)
pixel = frame[100, 200] # вернёт массив из 3 чисел, например [128, 64, 32]
Понимание того, что изображение — это просто массив чисел, фундаментально. Все операции компьютерного зрения — от простого порогового фильтра до свёрточных нейросетей — сводятся к математическим операциям с этим массивом.
4.3. Получение изображения с камеры
Вот базовый пример захвата видео с камеры:
import cv2
# Открытие камеры (0 — обычно встроенная веб-камера)
cap = cv2.VideoCapture(0)
if not cap.isOpened():
print("Error: Could not open camera")
exit()
while True:
ret, frame = cap.read()
if not ret:
print("Error: Can't receive frame")
break
cv2.imshow('Webcam', frame)
# Нажмите 'q' для выхода
if cv2.waitKey(1) == ord('q'):
break
cap.release()
cv2.destroyAllWindows()
Разберём по шагам:
-
cv2.VideoCapture(0)— открывает камеру с индексом 0. Индекс соответствует порядку камер в системе. -
cap.isOpened()— проверяет, удалось ли открыть камеру (может не удаться, если камера занята другой программой или не существует). -
cap.read()— считывает один кадр. Возвращает два значения:ret(True/False — успешно ли считан кадр) иframe(собственно изображение — тот самый NumPy-массив). -
cv2.imshow('Webcam', frame)— показывает кадр в окне с заголовком 'Webcam'. -
cv2.waitKey(1)— ждёт нажатия клавиши 1 миллисекунду. Без этого вызова окно не будет обновляться (это особенность работы оконной системы OpenCV). -
cap.release()— освобождает камеру. Это важно: если не освободить, другие программы не смогут получить доступ к камере. -
cv2.destroyAllWindows()— закрывает все окна OpenCV.
Попробуйте запустить этот пример. Обратите внимание на число 0 в VideoCapture(0) — это номер камеры. Если у вас несколько камер, попробуйте подставить 1 или 2. Может оказаться, что одна из камер — инфракрасная, и вы увидите непривычную чёрно-белую картинку (будет видно контуры, но не цвет). Это нормально — просто поменяйте номер.
4.4. Нанесение графических примитивов
Пока мы не занимаемся детектированием объектов — мы просто учимся что-то выводить на изображение. Позже мы соединим обнаружение объектов и выделение их рамками — а сейчас рисуем рамки и текст «вручную», чтобы понять, как это работает.
Рисование прямоугольника:
box_x1, box_y1 = 220, 50
box_x2, box_y2 = 440, 470
cv2.rectangle(frame, (box_x1, box_y1), (box_x2, box_y2), (255, 255, 0), 2)
Параметры функции cv2.rectangle:
-
frame— кадр, на котором рисуем (массив будет изменён на месте); -
(box_x1, box_y1)— координаты верхнего левого угла; -
(box_x2, box_y2)— координаты нижнего правого угла; -
(255, 255, 0)— цвет в формате BGR (синий=255, зелёный=255, красный=0, то есть голубой цвет); -
2— толщина линии в пикселях. Если указать-1, прямоугольник будет залит цветом целиком.
Добавление текста:
text = "teacher"
cv2.putText(frame, text, (box_x1, box_y1 - 10),
cv2.FONT_HERSHEY_SIMPLEX, 1.0, (0, 255, 0), 1)
Параметры cv2.putText:
-
frame— кадр; -
text— строка текста; -
(box_x1, box_y1 - 10)— координаты начала текста (левый нижний угол первого символа). Обратите внимание: мы указываем позицию на 10 пикселей выше прямоугольника, чтобы текст был над ним; -
cv2.FONT_HERSHEY_SIMPLEX— шрифт. Доступны такжеFONT_HERSHEY_DUPLEX,FONT_HERSHEY_COMPLEXи другие; -
1.0— масштаб шрифта; -
(0, 255, 0)— цвет (зелёный); -
1— толщина линий символов.
Также можно рисовать другие примитивы:
# Круг: центр, радиус, цвет, толщина (-1 для заливки)
cv2.circle(frame, (320, 240), 50, (0, 0, 255), 2)
# Линия: начало, конец, цвет, толщина
cv2.line(frame, (0, 0), (640, 480), (255, 0, 0), 1)
Практическое задание:
-
Запустите пример с прямоугольником и текстом.
-
Попробуйте изменить координаты, цвет, толщину линии.
-
Добавьте второй прямоугольник другого цвета.
-
Нарисуйте круг и линию.
-
Поэкспериментируйте с разными шрифтами (например,
cv2.FONT_HERSHEY_DUPLEX).
5. ROS и камера
5.1. Запуск ноды USB-камеры
Мы работаем с USB-камерами, и для ROS существует готовая нода usb_cam. Запускаем:
$ ros2 run usb_cam usb_cam_node_exe --ros-args -p video_device:=/dev/video0
Для просмотра изображения откройте RQT: Plugins → Visualization → Image View и выберите топик с изображением (обычно image_raw/compressed).
Попробуйте: запустите ноду камеры и откройте изображение в RQT. Убедитесь, что видите «живое» изображение — оно обновляется в реальном времени. Это означает, что данные с камеры успешно идут через ROS. Если изображение не появляется, проверьте путь к устройству (/dev/video0, /dev/video2 и т.д.) и попробуйте обновить список топиков в RQT.
5.2. Сжатые и несжатые изображения
Нода usb_cam публикует изображения в нескольких топиках одновременно:
-
image_raw— несжатое изображение (типsensor_msgs/msg/Image). Каждый кадр содержит полный массив пикселей без сжатия. При разрешении 640×480 с 3 каналами один кадр занимает ~900 КБ. -
image_raw/compressed— сжатое изображение в формате JPEG (типsensor_msgs/msg/CompressedImage). Один кадр занимает ~30-100 КБ в зависимости от качества сжатия.
Для работы по сети (а катамаран управляется именно по сети — через Wi-Fi) мы всегда используем сжатые изображения. Разница в трафике колоссальна: при 15 fps несжатые изображения создают поток ~13 МБ/с, сжатые — ~1 МБ/с. По беспроводному каналу это может быть разницей между работающей и неработающей системой.
5.3. Настройка параметров через YAML-файл
Видеокамера — устройство с множеством параметров: имя файла устройства, размеры кадра, частота кадров, формат. Хранить все эти настройки в аргументах командной строки неудобно. Правильный подход — вынести параметры в отдельный конфигурационный файл в формате YAML (Yet Another Markup Language — «ещё один язык разметки»). YAML широко применяется в ROS, он человекочитаем и понятен.
В папке config можно создать файл с параметрами ноды:
/**:
ros__parameters:
video_device: /dev/video0
image_width: 640
image_height: 480
framerate: 15.0
pixel_format: mjpeg2rgb
Разберём структуру:
-
/**:— параметры применяются ко всем нодам (двойная звёздочка означает «любое имя»); -
ros__parameters:— стандартный раздел параметров ROS2 (обратите внимание на двойное подчёркивание); -
далее перечислены параметры: устройство, размеры кадра, частота кадров;
-
pixel_format: mjpeg2rgb— формат пикселей. Камера отдаёт сжатые кадры в MJPEG, а нода конвертирует их в RGB. Это уменьшает нагрузку на канал связи между камерой и компьютером.
Запуск с файлом параметров из консоли:
$ ros2 run usb_cam usb_cam_node_exe --ros-args --params-file config/camera.yaml
5.4. Использование параметров в launch-файле
На практике мы обычно запускаем ноды не вручную из консоли, а через launch-файлы. В launch-файле можно указать путь к YAML-конфигурации:
from launch import LaunchDescription
from launch_ros.actions import Node
from launch_ros.substitutions import FindPackageShare
from launch.substitutions import PathJoinSubstitution
def generate_launch_description():
return LaunchDescription([
Node(
package='usb_cam',
executable='usb_cam_node_exe',
name='camera',
parameters=[PathJoinSubstitution([
FindPackageShare('lsn6'),
'config', 'camera.yaml'])
],
),
])
Здесь FindPackageShare('lsn6') находит папку установленного пакета lsn6, а PathJoinSubstitution собирает полный путь к файлу конфигурации. Этот подход удобен тем, что пути будут правильными на любом компьютере, где установлен пакет.
5.5. Работа с изображениями в ROS-ноде
Теперь давайте получим изображение из ROS-топика в нашей ноде и что-нибудь с ним сделаем. Работаем, по сути, так же, как и с другими данными в ROS — подписываемся на топик, создаём обработчик (callback).
Но есть один нюанс. OpenCV и ROS существовали много лет независимо, и форматы изображений у них разные: ROS хранит изображения в своих типах сообщений (Image, CompressedImage), а OpenCV работает с массивами NumPy. Для того чтобы «поженить» формат изображений ROS и формат OpenCV, используется cv_bridge — мост (bridge) между двумя мирами. Это конвертер одного формата в другой и обратно.
from sensor_msgs.msg import CompressedImage
import cv2
from cv_bridge import CvBridge
class CameraNode(Node):
def __init__(self):
super().__init__('camera_node')
# Создаём мост между ROS и OpenCV
self.bridge = CvBridge()
# Подписка на сжатое изображение
self.create_subscription(
CompressedImage,
'image_raw/compressed',
self.image_callback,
1 # Размер очереди = 1: берём только свежий кадр
)
# Публикация обработанного изображения
self.image_publisher = self.create_publisher(
CompressedImage,
'image_raw/changed/compressed',
10
)
def image_callback(self, msg):
# Конвертируем ROS-сообщение в формат OpenCV (NumPy-массив)
cv_image = self.bridge.compressed_imgmsg_to_cv2(msg)
# Теперь cv_image — обычный массив NumPy
# Можно применять любые операции OpenCV:
cv2.rectangle(cv_image, (220, 50), (440, 470), (255, 255, 0), 2)
cv2.putText(cv_image, "Hello from ROS!", (220, 40),
cv2.FONT_HERSHEY_SIMPLEX, 0.8, (0, 255, 0), 2)
# Конвертируем обратно и публикуем
result = self.bridge.cv2_to_compressed_imgmsg(cv_image)
self.image_publisher.publish(result)
Обратите внимание на размер очереди подписки — 1. Это означает, что если наша нода не успевает обрабатывать кадры, она будет пропускать промежуточные и брать только последний (свежий). Для задач реального времени это правильная стратегия: лучше обработать актуальный кадр, чем «догонять» очередь устаревших.
Всё то же самое, что мы делали с камерой напрямую в OpenCV, но теперь получение и отправка изображений — забота ROS. Мы подписываемся на сжатое изображение, конвертируем его в формат OpenCV с помощью bridge, обрабатываем, конвертируем обратно и публикуем в новый топик.
Практическое задание:
-
Запустите камеру через
usb_camи ноду из примераstep_1. -
В RQT откройте два потока: оригинальный (
image_raw/compressed) и обработанный (image_raw/changed/compressed). -
Убедитесь, что на обработанном потоке появились нарисованные элементы.
-
Измените код: добавьте свой текст, другой цвет рамки, круг.
6. Калибровка камеры
6.1. Зачем нужна калибровка
Эта тема напрямую не будет использована в текущем курсе, но она интересна и полезна для общего понимания — поэтому разберём её.
Любая камера вносит искажения (дисторсию) в изображение. Вы наверняка замечали, что на широкоугольных камерах (или на камерах типа «рыбий глаз» / fisheye) вертикальные линии становятся не вертикальными, а слегка изогнутыми — такой дугой. Даже обычная веб-камера вносит некоторые искажения: если включить её на полный экран, можно заметить, что стены на изображении не совсем прямые, хотя в реальности они, конечно, прямые.
Когда мы работаем с видеокамерой точно — например, измеряем расстояния или углы по изображению — эти искажения могут нам мешать. Их можно компенсировать при помощи калибровки: показать камере объект с известными параметрами (размерами), и алгоритм решит обратную задачу — какие математические операции нужно применить к изображению, чтобы оно стало «правильным».
В результате калибровки мы получаем:
-
матрицу внутренних параметров камеры (focal length, principal point) — описывает оптические свойства камеры;
-
коэффициенты искажений (distortion coefficients) — описывают, как именно линза «кривит» изображение.
Имея эти параметры, можно математически исправить дисторсию и получить «идеальное» изображение, как если бы камера была абсолютно точной.
6.2. Процедура калибровки
Используется классический метод с шахматной доской (checkerboard). Это не настоящая шахматная доска для игры — достаточно распечатать PDF (ссылка в конце главы) и наклеить на плоскую, жёсткую поверхность. Важно, чтобы поверхность была действительно плоской — если бумага прогибается, калибровка будет неточной.
Шаг 1. Запуск видеопотока
Запустите камеру через usb_cam:
$ ros2 run usb_cam usb_cam_node_exe --ros-args \
-p video_device:="/dev/video0" \
-p framerate:=30.0 \
-p pixel_format:="mjpeg2rgb" \
-r __ns:=/camera
Здесь -r __ns:=/camera добавляет namespace /camera ко всем топикам ноды. Это нужно для того, чтобы нода калибровки знала, где искать изображения.
Шаг 2. Запуск ноды калибровки
$ ros2 run camera_calibration cameracalibrator \
--size 8x6 --square 0.025 --no-service-check \
--ros-args --remap image:=/camera/image_raw
Параметры:
-
--size 8x6— количество внутренних углов на шахматной доске (не количество клеток, а именно углов — пересечений линий); -
--square 0.025— размер одного квадратика в метрах (2.5 см); -
--no-service-check— не проверять наличие сервисов (в нашем случае обязательный параметр); -
image:=/camera/image_raw— подписка на топик с изображением.
Шаг 3. Сбор данных
Откроется окно программы калибровки. Ваша задача — показывать шахматную доску камере с разных положений и углов. Программа будет обнаруживать углы доски и отмечать их на изображении цветными точками. Необходимо снять 40-50 кадров под разными углами.
Ваша задача — заполнить четыре индикатора:
-
X — перемещение доски по горизонтали (двигайте доску влево-вправо);
-
Y — перемещение по вертикали (двигайте вверх-вниз);
-
Size — приближение и удаление доски (подносите ближе и дальше от камеры);
-
Skew — наклон доски под разными углами (поворачивайте доску в разных плоскостях).
Каждый индикатор начинается красным и постепенно становится зелёным по мере набора данных.
Шаг 4. Калибровка и сохранение
Когда все четыре индикатора станут зелёными, загорится кнопка Calibrate. Нажмите её — алгоритм обработает собранные данные (это может занять некоторое время). Затем нажмите Save. Файл калибровки сохранится в /tmp/.
Перенесите файл калибровки в рабочую директорию:
$ mv /tmp/<folder>/out.yaml ~/.ros/camera_info/default_cam.yaml
После этого калибровочные данные будут автоматически подхватываться нодой камеры, и изображение будет корректироваться в реальном времени.
Совет: для калибровки нужно хорошее освещение. Если в комнате темно, камера будет плохо определять углы шахматной доски. Также старайтесь двигать доску плавно и не терять её из виду камеры.
Важно: если вы калибруете подводную камеру катамарана, калибровку нужно проводить под водой. Слой воды между камерой и стеклом бокса вносит дополнительные оптические искажения, которые отсутствуют на воздухе. Вода работает как дополнительная линза. Калибровка «на воздухе» для подводной камеры будет неточной.
7. Домашнее задание
-
Получите изображение с видеокамеры катамарана (или с USB-камеры) в ROS-ноде.
-
Нарисуйте прямоугольник по центру кадра.
-
Выведите произвольный текст под прямоугольником.
-
Задача со звёздочкой: выведите текущее время в качестве текста, чтобы оно обновлялось каждый кадр. Мы этого на занятии не делали, но думаю, вы справитесь — подсказка: модуль
datetimeиз стандартной библиотеки Python.
8. Дополнительные материалы
Calibration Checkerboard (PDF) https://markhedleyjones.com/media/calibration-checkerboard-collection/Checkerboard-A4-25mm-8x6.pdf |
https://markhedleyjones.com/media/calibration-checkerboard-collection/Checkerboard-A4-25mm-8x6.pdf |
Документация camera calibration (ROS) |
https://docs.ros.org/en/jazzy/p/image_pipeline/ |
Документация OpenCV camera calibration https://docs.opencv.org/4.x/dc/dbb/tutorial_py_calibration.html |
https://docs.opencv.org/4.x/dc/dbb/tutorial_py_calibration.html |
Документация OpenCV: рисование примитивов https://docs.opencv.org/4.x/d6/d6e/groupimgprocdraw.html |
https://docs.opencv.org/4.x/d6/d6e/group__imgproc__draw.html |
Документация usb_cam (ROS) |
https://docs.ros.org/en/jazzy/p/usb_cam/ |