face_tracker2.py 13 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333
  1. #!/usr/bin/env python
  2. """ face_tracker2.py - Version 1.1 2013-12-20
  3. Combines the OpenCV Haar face detector with Good Features to Track and Lucas-Kanade
  4. optical flow tracking. Keypoints are added and dropped according to simple statisical
  5. clustering rules.
  6. Created for the Pi Robot Project: http://www.pirobot.org
  7. Copyright (c) 2012 Patrick Goebel. All rights reserved.
  8. This program is free software; you can redistribute it and/or modify
  9. it under the terms of the GNU General Public License as published by
  10. the Free Software Foundation; either version 2 of the License, or
  11. (at your option) any later version.
  12. This program is distributed in the hope that it will be useful,
  13. but WITHOUT ANY WARRANTY; without even the implied warranty of
  14. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  15. GNU General Public License for more details at:
  16. http://www.gnu.org/licenses/gpl.html
  17. """
  18. import rospy
  19. import cv2
  20. import cv2.cv as cv
  21. import numpy as np
  22. from math import isnan, isinf
  23. from rbx1_vision.face_detector import FaceDetector
  24. from rbx1_vision.lk_tracker import LKTracker
  25. class FaceTracker(FaceDetector, LKTracker):
  26. def __init__(self, node_name):
  27. super(FaceTracker, self).__init__(node_name)
  28. self.n_faces = rospy.get_param("~n_faces", 1)
  29. self.show_text = rospy.get_param("~show_text", True)
  30. self.show_add_drop = rospy.get_param("~show_add_drop", False)
  31. self.feature_size = rospy.get_param("~feature_size", 1)
  32. self.use_depth_for_tracking = rospy.get_param("~use_depth_for_tracking", False)
  33. self.min_keypoints = rospy.get_param("~min_keypoints", 20)
  34. self.abs_min_keypoints = rospy.get_param("~abs_min_keypoints", 6)
  35. self.std_err_xy = rospy.get_param("~std_err_xy", 2.5)
  36. self.pct_err_z = rospy.get_param("~pct_err_z", 0.42)
  37. self.max_mse = rospy.get_param("~max_mse", 10000)
  38. self.add_keypoint_distance = rospy.get_param("~add_keypoint_distance", 10)
  39. self.add_keypoints_interval = rospy.get_param("~add_keypoints_interval", 1)
  40. self.drop_keypoints_interval = rospy.get_param("~drop_keypoints_interval", 1)
  41. self.expand_roi_init = rospy.get_param("~expand_roi", 1.02)
  42. self.expand_roi = self.expand_roi_init
  43. self.face_tracking = True
  44. self.frame_index = 0
  45. self.add_index = 0
  46. self.drop_index = 0
  47. self.keypoints = list()
  48. self.detect_box = None
  49. self.track_box = None
  50. self.grey = None
  51. self.prev_grey = None
  52. def process_image(self, cv_image):
  53. try:
  54. # Create a greyscale version of the image
  55. self.grey = cv2.cvtColor(cv_image, cv2.COLOR_BGR2GRAY)
  56. # Equalize the grey histogram to minimize lighting effects
  57. self.grey = cv2.equalizeHist(self.grey)
  58. # Step 1: Detect the face if we haven't already
  59. if self.detect_box is None:
  60. self.keypoints = list()
  61. self.track_box = None
  62. self.detect_box = self.detect_face(self.grey)
  63. else:
  64. # Step 2: If we aren't yet tracking keypoints, get them now
  65. if not self.track_box or not self.is_rect_nonzero(self.track_box):
  66. self.track_box = self.detect_box
  67. self.keypoints = self.get_keypoints(self.grey, self.track_box)
  68. # Store a copy of the current grey image used for LK tracking
  69. if self.prev_grey is None:
  70. self.prev_grey = self.grey
  71. # Step 3: If we have keypoints, track them using optical flow
  72. self.track_box = self.track_keypoints(self.grey, self.prev_grey)
  73. # Step 4: Drop keypoints that are too far from the main cluster
  74. if self.frame_index % self.drop_keypoints_interval == 0 and len(self.keypoints) > 0:
  75. ((cog_x, cog_y, cog_z), mse_xy, mse_z, score) = self.drop_keypoints(self.abs_min_keypoints, self.std_err_xy, self.max_mse)
  76. if score == -1:
  77. self.detect_box = None
  78. self.track_box = None
  79. return cv_image
  80. # Step 5: Add keypoints if the number is getting too low
  81. if self.frame_index % self.add_keypoints_interval == 0 and len(self.keypoints) < self.min_keypoints:
  82. self.expand_roi = self.expand_roi_init * self.expand_roi
  83. self.add_keypoints(self.track_box)
  84. else:
  85. self.frame_index += 1
  86. self.expand_roi = self.expand_roi_init
  87. # Store a copy of the current grey image used for LK tracking
  88. self.prev_grey = self.grey
  89. # Process any special keyboard commands for this module
  90. if self.keystroke != -1:
  91. try:
  92. cc = chr(self.keystroke & 255).lower()
  93. print cc
  94. if cc == 'c':
  95. self.keypoints = []
  96. self.track_box = None
  97. self.detect_box = None
  98. elif cc == 'd':
  99. self.show_add_drop = not self.show_add_drop
  100. except:
  101. pass
  102. except AttributeError:
  103. pass
  104. return cv_image
  105. def add_keypoints(self, track_box):
  106. # Look for any new keypoints around the current keypoints
  107. # Begin with a mask of all black pixels
  108. mask = np.zeros_like(self.grey)
  109. # Get the coordinates and dimensions of the current track box
  110. try:
  111. ((x,y), (w,h), a) = track_box
  112. except:
  113. try:
  114. x,y,w,h = track_box
  115. x = x + w / 2
  116. y = y + h / 2
  117. a = 0
  118. except:
  119. rospy.loginfo("Track box has shrunk to zero...")
  120. return
  121. x = int(x)
  122. y = int(y)
  123. # Expand the track box to look for new keypoints
  124. w_new = int(self.expand_roi * w)
  125. h_new = int(self.expand_roi * h)
  126. pt1 = (x - int(w_new / 2), y - int(h_new / 2))
  127. pt2 = (x + int(w_new / 2), y + int(h_new / 2))
  128. mask_box = ((x, y), (w_new, h_new), a)
  129. # Display the expanded ROI with a yellow rectangle
  130. if self.show_add_drop:
  131. cv2.rectangle(self.marker_image, pt1, pt2, cv.RGB(255, 255, 0))
  132. # Create a filled white ellipse within the track_box to define the ROI
  133. cv2.ellipse(mask, mask_box, cv.CV_RGB(255,255, 255), cv.CV_FILLED)
  134. if self.keypoints is not None:
  135. # Mask the current keypoints
  136. for x, y in [np.int32(p) for p in self.keypoints]:
  137. cv2.circle(mask, (x, y), 5, 0, -1)
  138. new_keypoints = cv2.goodFeaturesToTrack(self.grey, mask = mask, **self.gf_params)
  139. # Append new keypoints to the current list if they are not
  140. # too far from the current cluster
  141. if new_keypoints is not None:
  142. for x, y in np.float32(new_keypoints).reshape(-1, 2):
  143. distance = self.distance_to_cluster((x,y), self.keypoints)
  144. if distance > self.add_keypoint_distance:
  145. self.keypoints.append((x,y))
  146. # Briefly display a blue disc where the new point is added
  147. if self.show_add_drop:
  148. cv2.circle(self.marker_image, (x, y), 3, (255, 255, 0, 0), cv.CV_FILLED, 2, 0)
  149. # Remove duplicate keypoints
  150. self.keypoints = list(set(self.keypoints))
  151. def distance_to_cluster(self, test_point, cluster):
  152. min_distance = 10000
  153. for point in cluster:
  154. if point == test_point:
  155. continue
  156. # Use L1 distance since it is faster than L2
  157. distance = abs(test_point[0] - point[0]) + abs(test_point[1] - point[1])
  158. if distance < min_distance:
  159. min_distance = distance
  160. return min_distance
  161. def drop_keypoints(self, min_keypoints, outlier_threshold, mse_threshold):
  162. sum_x = 0
  163. sum_y = 0
  164. sum_z = 0
  165. sse = 0
  166. keypoints_xy = self.keypoints
  167. keypoints_z = self.keypoints
  168. n_xy = len(self.keypoints)
  169. n_z = n_xy
  170. # if self.use_depth_for_tracking:
  171. # if self.depth_image is None:
  172. # return ((0, 0, 0), 0, 0, -1)
  173. # If there are no keypoints left to track, start over
  174. if n_xy == 0:
  175. return ((0, 0, 0), 0, 0, -1)
  176. # Compute the COG (center of gravity) of the cluster
  177. for point in self.keypoints:
  178. sum_x = sum_x + point[0]
  179. sum_y = sum_y + point[1]
  180. mean_x = sum_x / n_xy
  181. mean_y = sum_y / n_xy
  182. mean_z = 0
  183. if self.use_depth_for_tracking and not self.depth_image is None:
  184. for point in self.keypoints:
  185. try:
  186. z = self.depth_image[point[1], point[0]]
  187. except:
  188. n_z = n_z - 1
  189. continue
  190. if not isnan(z):
  191. sum_z = sum_z + z
  192. else:
  193. n_z = n_z - 1
  194. continue
  195. try:
  196. mean_z = sum_z / n_z
  197. except:
  198. mean_z = -1
  199. else:
  200. mean_z = -1
  201. # Compute the x-y MSE (mean squared error) of the cluster in the camera plane
  202. for point in self.keypoints:
  203. sse = sse + (point[0] - mean_x) * (point[0] - mean_x) + (point[1] - mean_y) * (point[1] - mean_y)
  204. #sse = sse + abs((point[0] - mean_x)) + abs((point[1] - mean_y))
  205. # Get the average over the number of feature points
  206. mse_xy = sse / n_xy
  207. # The MSE must be > 0 for any sensible feature cluster
  208. if mse_xy == 0 or mse_xy > mse_threshold:
  209. return ((0, 0, 0), 0, 0, -1)
  210. # Throw away the outliers based on the x-y variance
  211. max_err = 0
  212. for point in self.keypoints:
  213. std_err = ((point[0] - mean_x) * (point[0] - mean_x) + (point[1] - mean_y) * (point[1] - mean_y)) / mse_xy
  214. if std_err > max_err:
  215. max_err = std_err
  216. if std_err > outlier_threshold:
  217. keypoints_xy.remove(point)
  218. if self.show_add_drop:
  219. # Briefly mark the removed points in red
  220. cv2.circle(self.marker_image, (point[0], point[1]), 3, (0, 0, 255), cv.CV_FILLED, 2, 0)
  221. try:
  222. keypoints_z.remove(point)
  223. n_z = n_z - 1
  224. except:
  225. pass
  226. n_xy = n_xy - 1
  227. # Now do the same for depth
  228. if self.use_depth_for_tracking and not self.depth_image is None:
  229. sse = 0
  230. for point in keypoints_z:
  231. try:
  232. z = self.depth_image[point[1], point[0]]
  233. sse = sse + (z - mean_z) * (z - mean_z)
  234. except:
  235. n_z = n_z - 1
  236. try:
  237. mse_z = sse / n_z
  238. except:
  239. mse_z = 0
  240. # Throw away the outliers based on depth using percent error
  241. # rather than standard error since depth values can jump
  242. # dramatically at object boundaries
  243. for point in keypoints_z:
  244. try:
  245. z = self.depth_image[point[1], point[0]]
  246. except:
  247. continue
  248. try:
  249. pct_err = abs(z - mean_z) / mean_z
  250. if pct_err > self.pct_err_z:
  251. keypoints_xy.remove(point)
  252. if self.show_add_drop:
  253. # Briefly mark the removed points in red
  254. cv2.circle(self.marker_image, (point[0], point[1]), 2, (0, 0, 255), cv.CV_FILLED)
  255. except:
  256. pass
  257. else:
  258. mse_z = -1
  259. self.keypoints = keypoints_xy
  260. # Consider a cluster bad if we have fewer than min_keypoints left
  261. if len(self.keypoints) < min_keypoints:
  262. score = -1
  263. else:
  264. score = 1
  265. return ((mean_x, mean_y, mean_z), mse_xy, mse_z, score)
  266. if __name__ == '__main__':
  267. try:
  268. node_name = "face_tracker"
  269. FaceTracker(node_name)
  270. rospy.spin()
  271. except KeyboardInterrupt:
  272. print "Shutting down face tracker node."
  273. cv.DestroyAllWindows()