Работа с камерой
СОВЕТ
В версии образа 0.20 пакет и сервис clever
был переименован в clover
. Для более ранних версий см. документацию для версии 0.19.
Для работы с основной камерой необходимо убедиться что она включена в файле ~/catkin_ws/src/clover/clover/launch/clover.launch
:
<arg name="main_camera" default="true"/>
Также нужно убедиться, что камера сфокусирована и для нее указано корректное расположение и ориентация.
При изменении launch-файла необходимо перезапустить пакет clover
:
sudo systemctl restart clover
Для мониторинга изображения с камеры можно использовать rqt или web_video_server.
Неисправности
Если изображение с камеры отсутствует, попробуйте проверить ее с помощью утилиты raspistill
.
Остановите сервисы Клевера:
sudo systemctl stop clover
Получите картинку с камеры утилитой raspistill
:
raspistill -o test.jpg
Если команда завершается с ошибкой, проверьте качество подключения шлейфа камеры к Raspberry Pi или замените его.
Настройки камеры
Ряд параметров камеры - размер изображения, максимальную частоту кадров, экспозицию - можно настроить в файле main_camera.launch
. Список настраиваемых параметров можно посмотреть в репозитории cv_camera.
Параметры, не указанные в этом списке, можно указывать через код параметра OpenCV. Например, для установки фиксированной экспозиции добавьте следующие параметры в ноду камеры:
<param name="property_0_code" value="21"/> <!-- property code 21 is CAP_PROP_AUTO_EXPOSURE -->
<param name="property_0_value" value="0.25"/> <!-- property values are normalized as per OpenCV specs, even for "menu" controls; 0.25 means "use manual exposure" -->
<param name="cv_cap_prop_exposure" value="0.3"/> <!-- set exposure to 30% of maximum value -->
Компьютерное зрение
Для реализации алгоритмов компьютерного зрения рекомендуется использовать предустановленную на образ SD-карты библиотеку OpenCV.
Python
Основная статья: http://wiki.ros.org/cv_bridge/Tutorials/ConvertingBetweenROSImagesAndOpenCVImagesPython.
Пример создания подписчика на топик с изображением с основной камеры для обработки с использованием OpenCV:
import rospy
import cv2
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
rospy.init_node('computer_vision_sample')
bridge = CvBridge()
def image_callback(data):
cv_image = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
# Do any image processing with cv2...
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback)
rospy.spin()
Для отладки обработки изображения можно публиковать отдельный топик с обработанным изображением:
image_pub = rospy.Publisher('~debug', Image)
Публикация обработанного изображения (в конце функции image_callback):
image_pub.publish(bridge.cv2_to_imgmsg(cv_image, 'bgr8'))
Получаемые изображения можно просматривать используя web_video_server.
Получение одного кадра
Существует возможность единоразового получения кадра с камеры. Этот способ работает медленнее, чем подписка на топик; его не следует применять в случае необходимости постоянной обработки изображений.
import rospy
from sensor_msgs.msg import Image
from cv_bridge import CvBridge
rospy.init_node('computer_vision_sample')
bridge = CvBridge()
# ...
# Получение кадра:
img = bridge.imgmsg_to_cv2(rospy.wait_for_message('main_camera/image_raw', Image), 'bgr8')
Примеры
Работа с QR-кодами
СОВЕТ
Для высокоскоростного распознавания и позиционирования лучше использовать ArUco-маркеры.
Для программирования различных действий коптера при детектировании нужных QR-кодов можно использовать библиотеку pyZBar. Она уже установлена в последнем образе для Raspberry Pi.
Распознавание QR-кодов на Python:
import rospy
from pyzbar import pyzbar
from cv_bridge import CvBridge
from sensor_msgs.msg import Image
bridge = CvBridge()
rospy.init_node('barcode_test')
# Image subscriber callback function
def image_callback(data):
cv_image = bridge.imgmsg_to_cv2(data, 'bgr8') # OpenCV image
barcodes = pyzbar.decode(cv_image)
for barcode in barcodes:
b_data = barcode.data.decode("utf-8")
b_type = barcode.type
(x, y, w, h) = barcode.rect
xc = x + w/2
yc = y + h/2
print("Found {} with data {} with center at x={}, y={}".format(b_type, b_data, xc, yc))
image_sub = rospy.Subscriber('main_camera/image_raw', Image, image_callback, queue_size=1)
rospy.spin()
Скрипт будет занимать 100% процессора. Для искусственного замедления работы скрипта можно запустить throttling кадров с камеры, например, в 5 Гц (main_camera.launch
):
<node pkg="topic_tools" name="cam_throttle" type="throttle"
args="messages main_camera/image_raw 5.0 main_camera/image_raw_throttled"/>
Топик для подписчика в этом случае необходимо поменять на main_camera/image_raw_throttled
.
Запись видео
Для записи видео может использована нода video_recorder
из пакета image_view
:
rosrun image_view video_recorder image:=/main_camera/image_raw
Видео будет сохранено в файл output.avi
. В аргументе image
указывается название топика для записи видео.