機器視覺是一個非常複雜的主題,需要比較專業的計算機圖形學相關知識,在ROS By Example Volume 1這本書中提供了比較好的入門範例,所以我們將按照此書中所介紹的例子開啓我們Diego的機器視覺之旅,後面逐步增加比較複雜的內容。
我們首先來實現實現書中所講到的人臉檢測、特徵值獲取、人臉跟蹤,機器人跟隨等功能,由於此書中所使用的代碼依賴於opencv2.4,但在Diego我們安裝的是ROS kinetic,默認安裝了Opencv3,所以本人對其源代碼進行了移植,使其可以在Opencv3環境中正確編譯,移植後的代碼請見github Diego1 plus下的diego_vision目錄。
1.關於圖像格式
ROS有自己圖像格式,但比較流行的都是使用opencv來對圖像視頻進行處理,因爲其封裝了大量先進的圖像算法,而且還是開源的,所以首先就需要將ROS的圖像格式轉換爲opencv的圖像格式,無奇不有的ROS已經提供了cv_bridge這個包來完成轉換的任務,而且支持opencv3版本。如果安裝的是ros-kinetic-desktop-full的版本,那麼這個包已經安裝好了,如果沒有ros-kinetic-desktop-full則需要單獨安裝,這裏建議大家git clone源代碼安裝,因爲如果用apt-get安裝的話,會同時安裝opencv2.4版本,這會造成一些版本的衝突,有關cv_bridge的使用方法,可以參考官方的示例代碼。
2.ros2opencv3.py通用功能包
將原來的ros2opencv2.py針對opencv2.4的代碼,移植到opencv3d的環境下,同時重命名爲ros2opencv3.py,類名也改爲ROS2OpenCV3,源代碼請見GitHub,如下是主要函數功能說明:
init:ROS2OpenCV3的初始化函數,設置相關參數,初始化ROS 節點,訂閱RGB及RGBD消息主題
on_mouse_click:鼠標事件,用戶可以通過鼠標在視頻窗口中畫出ROI
image_callback:RGB圖像的回調函數
depth_callback:深度圖像的回調函數
convert_image:將RGB圖像從ROS格式轉換爲opencv格式
convert_depth_image:將深度圖像從ROS格式轉換opencv格式
publish_roi:發佈ROI(Region Of Interesting)消息,此消息描述圖像中我們感興趣的區域
process_image:RGB圖像的處理函數,這裏未做任何處理,留做後面繼承類擴展
process_depth_image:深度圖像的處理函數,這裏未做任何處理,留做後面繼承類擴展
display_selection:用矩形顯示用戶在視頻上選擇的區域,用小圓點顯示用戶在圖像上點擊的區域
is_rect_nonzero:判斷矩形區域是否有效
cvBox2D_to_cvRect:將cvBox2D數據結構轉換爲cvRect
cvRect_to_cvBox2D:將cvRect數據結構轉換爲cvBox2D
3.人臉識別
3.1 人臉識別的方法
opencv人臉檢測的一般步驟是
分類器暨Haar特徵分類器,人臉的Haar特徵分類器就是一個XML文件,該文件中會描述人臉的Haar特徵值,opencv算法針對圖片中的數據匹配分類器,從而識別出人臉,我們這裏使用到三個分類器
haarcascade_frontalface_alt2.xml
haarcascade_frontalface_alt.xml
haarcascade_profileface.xml
從攝像頭讀入圖片視頻後,我們首先需要對圖像轉換成灰度圖像,然後在進行特徵獲取,最後調用opencv的detectMultiScale既可以檢測人臉
3.2 代碼分析
代碼已經移植到opencv3,可以參見github
3.2.1完整的face_detector.py代碼
#!/usr/bin/env python
import rospy
import cv2
from ros2opencv3 import ROS2OpenCV3
class FaceDetector(ROS2OpenCV3):
def __init__(self, node_name):
super(FaceDetector, self).__init__(node_name)
# Get the paths to the cascade XML files for the Haar detectors.
# These are set in the launch file.
cascade_1 = rospy.get_param("~cascade_1", "")
cascade_2 = rospy.get_param("~cascade_2", "")
cascade_3 = rospy.get_param("~cascade_3", "")
# Initialize the Haar detectors using the cascade files
self.cascade_1 = cv2.CascadeClassifier(cascade_1)
self.cascade_2 = cv2.CascadeClassifier(cascade_2)
self.cascade_3 = cv2.CascadeClassifier(cascade_3)
# Set cascade parameters that tend to work well for faces.
# Can be overridden in launch file
self.haar_scaleFactor = rospy.get_param("~haar_scaleFactor", 1.3)
self.haar_minNeighbors = rospy.get_param("~haar_minNeighbors", 3)
self.haar_minSize = rospy.get_param("~haar_minSize", 30)
self.haar_maxSize = rospy.get_param("~haar_maxSize", 150)
# Store all parameters together for passing to the detector
self.haar_params = dict(scaleFactor = self.haar_scaleFactor,
minNeighbors = self.haar_minNeighbors,
flags = cv2.CASCADE_DO_CANNY_PRUNING,
minSize = (self.haar_minSize, self.haar_minSize),
maxSize = (self.haar_maxSize, self.haar_maxSize)
)
# Do we should text on the display?
self.show_text = rospy.get_param("~show_text", True)
# Intialize the detection box
self.detect_box = None
# Track the number of hits and misses
self.hits = 0
self.misses = 0
self.hit_rate = 0
def process_image(self, cv_image):
# Create a greyscale version of the image
grey = cv2.cvtColor(cv_image, cv2.COLOR_BGR2GRAY)
# Equalize the histogram to reduce lighting effects
grey = cv2.equalizeHist(grey)
# Attempt to detect a face
self.detect_box = self.detect_face(grey)
# Did we find one?
if self.detect_box is not None:
self.hits += 1
else:
self.misses += 1
# Keep tabs on the hit rate so far
self.hit_rate = float(self.hits) / (self.hits + self.misses)
return cv_image
def detect_face(self, input_image):
# First check one of the frontal templates
if self.cascade_1:
faces = self.cascade_1.detectMultiScale(input_image, **self.haar_params)
# If that fails, check the profile template
if len(faces) == 0 and self.cascade_3:
faces = self.cascade_3.detectMultiScale(input_image, **self.haar_params)
# If that also fails, check a the other frontal template
if len(faces) == 0 and self.cascade_2:
faces = self.cascade_2.detectMultiScale(input_image, **self.haar_params)
# The faces variable holds a list of face boxes.
# If one or more faces are detected, return the first one.
if len(faces) > 0:
face_box = faces[0]
else:
# If no faces were detected, print the "LOST FACE" message on the screen
if self.show_text:
font_face = cv2.FONT_HERSHEY_SIMPLEX
font_scale = 0.5
cv2.putText(self.marker_image, "LOST FACE!",
(int(self.frame_size[0] * 0.65), int(self.frame_size[1] * 0.9)),
font_face, font_scale, (255, 50, 50))
face_box = None
# Display the hit rate so far
if self.show_text:
font_face = cv2.FONT_HERSHEY_SIMPLEX
font_scale = 0.5
cv2.putText(self.marker_image, "Hit Rate: " +
str(trunc(self.hit_rate, 2)),
(20, int(self.frame_size[1] * 0.9)),
font_face, font_scale, (255, 255, 0))
return face_box
def trunc(f, n):
'''Truncates/pads a float f to n decimal places without rounding'''
slen = len('%.*f' % (n, f))
return float(str(f)[:slen])
if __name__ == '__main__':
try:
node_name = "face_detector"
FaceDetector(node_name)
rospy.spin()
except KeyboardInterrupt:
print "Shutting down face detector node."
cv2.destroyAllWindows()
3.2.2代碼解釋
FaceDetector類繼承自ROS2OpenCV3,重寫了process_image,對圖片進行灰度轉換,同時新增了detect_face函數進行人臉檢測,在類的初始化代碼中載入分類器,cascade_1,cascade_2,cascade_3定義了三個分類器的位置
# Get the paths to the cascade XML files for the Haar detectors.
# These are set in the launch file.
cascade_1 = rospy.get_param("~cascade_1", "")
cascade_2 = rospy.get_param("~cascade_2", "")
cascade_3 = rospy.get_param("~cascade_3", "")
# Initialize the Haar detectors using the cascade files
self.cascade_1 = cv2.CascadeClassifier(cascade_1)
self.cascade_2 = cv2.CascadeClassifier(cascade_2)
self.cascade_3 = cv2.CascadeClassifier(cascade_3)
在process_image函數中對圖片進行灰度轉換
# Create a greyscale version of the image
grey = cv2.cvtColor(cv_image, cv2.COLOR_BGR2GRAY)
# Equalize the histogram to reduce lighting effects
grey = cv2.equalizeHist(grey)
在detect_face函數中進行人臉檢測
if self.cascade_1:
faces = self.cascade_1.detectMultiScale(input_image, **self.haar_params)
# If that fails, check the profile template
if len(faces) == 0 and self.cascade_3:
faces = self.cascade_3.detectMultiScale(input_image, **self.haar_params)
# If that also fails, check a the other frontal template
if len(faces) == 0 and self.cascade_2:
faces = self.cascade_2.detectMultiScale(input_image, **self.haar_params)
在detect_face函數中顯示信息
# The faces variable holds a list of face boxes.
# If one or more faces are detected, return the first one.
if len(faces) > 0:
face_box = faces[0]
else:
# If no faces were detected, print the "LOST FACE" message on the screen
if self.show_text:
font_face = cv2.FONT_HERSHEY_SIMPLEX
font_scale = 0.5
cv2.putText(self.marker_image, "LOST FACE!",
(int(self.frame_size[0] * 0.65), int(self.frame_size[1] * 0.9)),
font_face, font_scale, (255, 50, 50))
face_box = None
# Display the hit rate so far
if self.show_text:
font_face = cv2.FONT_HERSHEY_SIMPLEX
font_scale = 0.5
cv2.putText(self.marker_image, "Hit Rate: " +
str(trunc(self.hit_rate, 2)),
(20, int(self.frame_size[1] * 0.9)),
font_face, font_scale, (255, 255, 0))
return face_box
父類ROS2OpenCV3 的image_callback函數將會把檢測到人臉位置用矩形線框表示出來
4. 載入人臉檢測節點
首先確保啓動xtion啓動,可以通過如下代碼啓動:
roslaunch diego_vision openni_node.launch
face_detector.launch文件可見github的diego_vision/launch目錄
<launch>
<node pkg="diego_vision" name="face_detector" type="face_detector.py" output="screen">
<remap from="input_rgb_image" to="/camera/rgb/image_color" />
<rosparam>
haar_scaleFactor: 1.3
haar_minNeighbors: 3
haar_minSize: 30
haar_maxSize: 150
</rosparam>
<param name="cascade_1" value="$(find diego_vision)/data/haar_detectors/haarcascade_frontalface_alt2.xml" />
<param name="cascade_2" value="$(find diego_vision)/data/haar_detectors/haarcascade_frontalface_alt.xml" />
<param name="cascade_3" value="$(find diego_vision)/data/haar_detectors/haarcascade_profileface.xml" />
</node>
</launch>
啓動人臉檢測節點
roslaunch diego_vision face_detector.launch
啓動後平面將會顯示一個視頻窗體,可以檢測到攝像頭捕捉到的人臉,並且用矩形標識出來