ROS OpenCV - eiichiromomma/CVMLAB GitHub Wiki

(ROS) OpenCV

usb_camが必要なのでaptで入れておく。

とりあえず表示

ターミナルを開いて

roscore

別のターミナルで

rosparam set usb_cam/pixel_format "yuyv"
rosrun usb_cam usb_cam_node

で更に別のターミナルを開き

rostopic list

でusb_camがあるのを確認

rosrun image_view image_view image:=/usb_cam/image_raw

でウィンドウが開いてカメラの内容が表示されたら成功

OpenCVに渡す

cv_bridgeを入れておく。

image_viewのターミナルでCtrl+Cを押して停止させる。

follower_opencv.py (オライリーの「プログラミングROS」を参考にした)

#!/usr/bin/env python
import rospy
from sensor_msgs.msg import Image
import cv2, cv_bridge

class Follower:
    def __init__(self):
        self.bridge = cv_bridge.CvBridge()
        # ここにnamedWindowを宣言するサンプルもあるが不要
        # cv2.namedWindow("window", 1)
        # camera/rgb/image_rawの場合もある(usb以外のカメラ)
        self.image_sub = rospy.Subscriber('usb_cam/image_raw', Image, self.image_callback, queue_size=1)
    def image_callback(self, msg):
        # desired_encodingの指定は必須
        image = self.bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
        # ここに処理を書けば良い
        cv2.imshow("window", image)
        cv2.waitKey(3)

rospy.init_node('follower')
follower = Follower()
rospy.spin()

顔検出

あとはOpenCVの知識があればどうにでもなる。 haarcascade_frontalface_default.xmlは以下のソースと同じ場所に置いておくか、パスを指定する。相当スペックの高いマシンでないと遅延が生じるのでdetectMultiScaleに scaleFactor=1.11, minNeighbors=1, minSize=(100, 100) のような感じで処理を軽くする。それでも遅延する場合はresizeする。

follower_facedet.py

#!/usr/bin/env python
import rospy
from sensor_msgs.msg import Image
import cv2, cv_bridge

class Follower:
    def __init__(self):
        self.bridge = cv_bridge.CvBridge()
        self.image_sub = rospy.Subscriber('usb_cam/image_raw', Image, self.image_callback, queue_size=1)
        self.fdet = cv2.CascadeClassifier('haarcascade_frontalface_default.xml')
    def image_callback(self, msg):
        image = self.bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
        # グレーにするのもダルいのでGreenで代用
        # detectionの細かい設定はここでやる
        faces = self.fdet.detectMultiScale(image[:,:,1], scaleFactor=1.11, minNeighbors=1, minSize=(100, 100) )
        # 顔の場所に四角形
        for (x, y, w, h) in faces:
            cv2.rectangle(image, (x, y), (x+w, y+h), (0, 0, 255), 2)
        cv2.imshow("window", image)
        cv2.waitKey(3)

rospy.init_node('follower')
follower = Follower()
rospy.spin()

人検出

HOGの計算が苦しいので画像サイズを小さくして、更にオプションで処理を軽くする。

#!/usr/bin/env python
import rospy
from sensor_msgs.msg import Image
import cv2, cv_bridge

class Follower:
    def __init__(self):
        self.bridge = cv_bridge.CvBridge()
        self.image_sub = rospy.Subscriber('usb_cam/image_raw', Image, self.image_callback, queue_size=1)
        self.hog = cv2.HOGDescriptor()
        self.hog.setSVMDetector(cv2.HOGDescriptor_getDefaultPeopleDetector())

    def image_callback(self, msg):
        image = self.bridge.imgmsg_to_cv2(msg, desired_encoding='bgr8')
        image = cv2.resize(image, (320, 240))
        hogParams = {'winStride': (8, 8), 'scale': 1.5}
        people, r = self.hog.detectMultiScale(image[:, :, 1], **hogParams)
        for (x, y, w, h) in people:
            cv2.rectangle(image, (x, y), (x+w, y+h), (0, 0, 255), 2)
        cv2.imshow("window", image)
        cv2.waitKey(1)

rospy.init_node('follower')
follower = Follower()
rospy.spin()