camshift.py 6.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166
  1. #!/usr/bin/env python
  2. """ camshift_node.py - Version 1.1 2013-12-20
  3. Modification of the ROS OpenCV Camshift example using cv_bridge and publishing the ROI
  4. coordinates to the /roi topic.
  5. """
  6. import rospy
  7. import cv2
  8. from cv2 import cv as cv
  9. from rbx1_vision.ros2opencv2 import ROS2OpenCV2
  10. from std_msgs.msg import String
  11. from sensor_msgs.msg import Image
  12. import numpy as np
  13. class CamShiftNode(ROS2OpenCV2):
  14. def __init__(self, node_name):
  15. ROS2OpenCV2.__init__(self, node_name)
  16. self.node_name = node_name
  17. # The minimum saturation of the tracked color in HSV space,
  18. # as well as the min and max value (the V in HSV) and a
  19. # threshold on the backprojection probability image.
  20. self.smin = rospy.get_param("~smin", 85)
  21. self.vmin = rospy.get_param("~vmin", 50)
  22. self.vmax = rospy.get_param("~vmax", 254)
  23. self.threshold = rospy.get_param("~threshold", 50)
  24. # Create a number of windows for displaying the histogram,
  25. # parameters controls, and backprojection image
  26. cv.NamedWindow("Histogram", cv.CV_WINDOW_NORMAL)
  27. cv.MoveWindow("Histogram", 700, 50)
  28. cv.NamedWindow("Parameters", 0)
  29. cv.MoveWindow("Parameters", 700, 325)
  30. cv.NamedWindow("Backproject", 0)
  31. cv.MoveWindow("Backproject", 700, 600)
  32. # Create the slider controls for saturation, value and threshold
  33. cv.CreateTrackbar("Saturation", "Parameters", self.smin, 255, self.set_smin)
  34. cv.CreateTrackbar("Min Value", "Parameters", self.vmin, 255, self.set_vmin)
  35. cv.CreateTrackbar("Max Value", "Parameters", self.vmax, 255, self.set_vmax)
  36. cv.CreateTrackbar("Threshold", "Parameters", self.threshold, 255, self.set_threshold)
  37. # Initialize a number of variables
  38. self.hist = None
  39. self.track_window = None
  40. self.show_backproj = False
  41. # These are the callbacks for the slider controls
  42. def set_smin(self, pos):
  43. self.smin = pos
  44. def set_vmin(self, pos):
  45. self.vmin = pos
  46. def set_vmax(self, pos):
  47. self.vmax = pos
  48. def set_threshold(self, pos):
  49. self.threshold = pos
  50. # The main processing function computes the histogram and backprojection
  51. def process_image(self, cv_image):
  52. try:
  53. # First blur the image
  54. frame = cv2.blur(cv_image, (5, 5))
  55. # Convert from RGB to HSV space
  56. hsv = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV)
  57. # Create a mask using the current saturation and value parameters
  58. mask = cv2.inRange(hsv, np.array((0., self.smin, self.vmin)), np.array((180., 255., self.vmax)))
  59. # If the user is making a selection with the mouse,
  60. # calculate a new histogram to track
  61. if self.selection is not None:
  62. x0, y0, w, h = self.selection
  63. x1 = x0 + w
  64. y1 = y0 + h
  65. self.track_window = (x0, y0, x1, y1)
  66. hsv_roi = hsv[y0:y1, x0:x1]
  67. mask_roi = mask[y0:y1, x0:x1]
  68. self.hist = cv2.calcHist( [hsv_roi], [0], mask_roi, [16], [0, 180] )
  69. cv2.normalize(self.hist, self.hist, 0, 255, cv2.NORM_MINMAX);
  70. self.hist = self.hist.reshape(-1)
  71. self.show_hist()
  72. if self.detect_box is not None:
  73. self.selection = None
  74. # If we have a histogram, track it with CamShift
  75. if self.hist is not None:
  76. # Compute the backprojection from the histogram
  77. backproject = cv2.calcBackProject([hsv], [0], self.hist, [0, 180], 1)
  78. # Mask the backprojection with the mask created earlier
  79. backproject &= mask
  80. # Threshold the backprojection
  81. ret, backproject = cv2.threshold(backproject, self.threshold, 255, cv.CV_THRESH_TOZERO)
  82. x, y, w, h = self.track_window
  83. if self.track_window is None or w <= 0 or h <=0:
  84. self.track_window = 0, 0, self.frame_width - 1, self.frame_height - 1
  85. # Set the criteria for the CamShift algorithm
  86. term_crit = ( cv2.TERM_CRITERIA_EPS | cv2.TERM_CRITERIA_COUNT, 10, 1 )
  87. # Run the CamShift algorithm
  88. self.track_box, self.track_window = cv2.CamShift(backproject, self.track_window, term_crit)
  89. # Display the resulting backprojection
  90. cv2.imshow("Backproject", backproject)
  91. except:
  92. pass
  93. return cv_image
  94. def show_hist(self):
  95. bin_count = self.hist.shape[0]
  96. bin_w = 24
  97. img = np.zeros((256, bin_count*bin_w, 3), np.uint8)
  98. for i in xrange(bin_count):
  99. h = int(self.hist[i])
  100. cv2.rectangle(img, (i*bin_w+2, 255), ((i+1)*bin_w-2, 255-h), (int(180.0*i/bin_count), 255, 255), -1)
  101. img = cv2.cvtColor(img, cv2.COLOR_HSV2BGR)
  102. cv2.imshow('Histogram', img)
  103. def hue_histogram_as_image(self, hist):
  104. """ Returns a nice representation of a hue histogram """
  105. histimg_hsv = cv.CreateImage((320, 200), 8, 3)
  106. mybins = cv.CloneMatND(hist.bins)
  107. cv.Log(mybins, mybins)
  108. (_, hi, _, _) = cv.MinMaxLoc(mybins)
  109. cv.ConvertScale(mybins, mybins, 255. / hi)
  110. w,h = cv.GetSize(histimg_hsv)
  111. hdims = cv.GetDims(mybins)[0]
  112. for x in range(w):
  113. xh = (180 * x) / (w - 1) # hue sweeps from 0-180 across the image
  114. val = int(mybins[int(hdims * x / w)] * h / 255)
  115. cv2.rectangle(histimg_hsv, (x, 0), (x, h-val), (xh,255,64), -1)
  116. cv2.rectangle(histimg_hsv, (x, h-val), (x, h), (xh,255,255), -1)
  117. histimg = cv2.cvtColor(histimg_hsv, cv.CV_HSV2BGR)
  118. return histimg
  119. if __name__ == '__main__':
  120. try:
  121. node_name = "camshift"
  122. CamShiftNode(node_name)
  123. try:
  124. rospy.init_node(node_name)
  125. except:
  126. pass
  127. rospy.spin()
  128. except KeyboardInterrupt:
  129. print "Shutting down vision node."
  130. cv.DestroyAllWindows()