matchtemplate.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import roslib; roslib.load_manifest('jsk_perception')
4 import rospy
5 import numpy as np
6 try:
7  import thread
8 except:
9  import _thread as thread
10 from sensor_msgs.msg import Image
11 from geometry_msgs.msg import *
12 from jsk_recognition_msgs.msg import Rect
13 import cv2
14 from cv_bridge import CvBridge, CvBridgeError
15 
16 from dynamic_reconfigure.server import Server as DynamicReconfigureServer
17 from dynamic_reconfigure.msg import SensorLevels
18 from jsk_perception.cfg import matchtemplateConfig as ConfigType
19 
20 # you can set below options for each templates
21 # color space: mono8,bgr8,bgra8,hsv,hsva (OpenCV expects bgr)
22 # template size: tuple (x,y,width,height)
23 # search area: tuple (x,y,width,height)
24 # search topic: (TODO)
25 # match method: 6type
26 
27 # publish topic:
28 # current_template [sensor_msgs/Image]
29 # result [geometry_msgs/TransformStamped]
30 # debug_image [sensor_msgs/Image]
31 
32 # subscribe topic:
33 # reference [sensor_msgs/Image]
34 # search [sensor_msgs/Image]
35 # set_reference_point [geometry_msgs/PointStamped]
36 # set_search_rect [jsk_recognition_msgs/Rect]
37 
38 # return (1st-val,1st-loc,2nd-val,2nd-loc)
39 def _MinMaxLock2nd(arr,ex_size,is_min):
40  if is_min: idx = 0
41  else: idx = 1
42  status = cv2.minMaxLoc(arr)
43  pt1 = (max(status[2+idx][0]-int(ex_size[0]/2),0),
44  max(status[2+idx][1]-int(ex_size[1]/2),0))
45  pt2 = (min(status[2+idx][0]+int(ex_size[0]/2),arr.shape[1]),
46  min(status[2+idx][1]+int(ex_size[1]/2),arr.shape[0]))
47  mask = np.ones((arr.shape[0], arr.shape[1]), dtype=np.uint8) * 255
48  mask[pt1[0]:pt2[0], pt1[1]:pt2[1]] = 0
49  status2 = cv2.minMaxLoc(arr, mask)
50  return (status[0+idx],status2[0+idx],status[2+idx],status2[2+idx])
51 
52 def MinLock2nd(arr,ex_size):
53  return _MinMaxLock2nd(arr,ex_size,True)
54 def MaxLock2nd(arr,ex_size):
55  return _MinMaxLock2nd(arr,ex_size,False)
56 
57 
59  bridge = CvBridge()
60 
61  def __init__(self):
62  self.lockobj = thread.allocate_lock()
63  # variables
64  self.reference_image_msg = None
65  self.templates = {} # frame_id : ref_image,ser_frame,ser_rect
66  self.clock = [rospy.Time.now()]
67 
68  # publisher
69  self.reference_pub = rospy.Publisher(
70  "current_template", Image, queue_size=1)
71  self.result_pub = rospy.Publisher(
72  "result", TransformStamped, queue_size=1)
73  self.debug_pub = rospy.Publisher("debug_image", Image, queue_size=1)
74 
75  # subscriber
76  self.reference_image_sub = rospy.Subscriber(rospy.resolve_name("reference"),
77  Image,self.ref_image_callback,queue_size=1)
78  self.search_image_sub = rospy.Subscriber(rospy.resolve_name("search"),
79  Image,self.ser_image_callback,queue_size=1)
80  self.reference_point_sub = rospy.Subscriber(
81  rospy.resolve_name("set_reference_point"),
82  PointStamped,self.set_reference_point_callback,queue_size=1)
83  self.search_sub = rospy.Subscriber(rospy.resolve_name("set_search_rect"),
84  Rect,self.set_search_callback,queue_size=1)
85 
86  self.server = DynamicReconfigureServer(ConfigType, self.reconfigure)
87 
88  # general template modifier function
89  def set_template (self, ref_id='', ref_image=None, ref_rect=None,
90  ser_frame=None, ser_rect=None, color=None, method=None):
91  if ref_id not in self.templates:
92  self.templates[ref_id] = {'ref_orig':None,'ref_point':None,'ref_image':None,
93  'ser_frame':None, 'ser_rect':None,
94  'color':'mono8', 'method':cv2.TM_SQDIFF_NORMED} # normalized SSD
95  color_changed = True
96  else:
97  color_changed = (self.templates[ref_id]['color'] != color) and (color != None)
98 
99  something_changed = (ref_image is not None) or \
100  (ref_rect is not None) or color_changed
101 
102  # parameters for template
103  if ref_image is not None:
104  self.templates[ref_id]['ref_orig'] = ref_image.copy()
105  else:
106  ref_image = self.templates[ref_id]['ref_orig'] # old image can be set here
107 
108  if color != None:
109  if ref_image is not None and ref_image.ndim == 2:
110  color = 'mono8'
111  self.templates[ref_id]['color'] = color
112  else:
113  color = self.templates[ref_id]['color']
114 
115  # copy template from reference original image
116  if (ref_rect is not None) and (ref_image is not None) and \
117  something_changed:
118  ref_rect = (min(max(0,ref_rect[0]),ref_image.shape[1]-ref_rect[2]),
119  min(max(0,ref_rect[1]),ref_image.shape[0]-ref_rect[3]),
120  ref_rect[2],ref_rect[3])
121  ref_image_rect = ref_image[
122  ref_rect[1]:ref_rect[1] + ref_rect[3],
123  ref_rect[0]:ref_rect[0] + ref_rect[2]].copy()
124  if color == 'bgr8' or (color == 'mono8' and ref_image.ndim == 2):
125  template_image = ref_image_rect
126  elif color == 'mono8':
127  template_image = cv2.cvtColor(
128  ref_image_rect, cv2.COLOR_BGR2GRAY)
129  elif color == 'hsv8':
130  template_image = cv2.cvtColor(
131  ref_image_rect, cv2.COLOR_BGR2HSV)
132 
133  self.templates[ref_id]['ref_point'] = (ref_rect[0]+int(ref_rect[2]/2),
134  ref_rect[1]+int(ref_rect[3]/2))
135  self.templates[ref_id]['ref_image'] = template_image
136  rospy.loginfo("set ref_image id=%s, rect=%s", ref_id, ref_rect);
137 
138  # matching parameters
139  if ser_frame != None:
140  self.templates[ref_id]['ser_frame'] = ser_frame
141  rospy.loginfo("set ser_frame id=%s frame=%s", ref_id, ser_frame);
142  if ser_rect != None:
143  self.templates[ref_id]['ser_rect'] = ser_rect
144  #rospy.loginfo("set ser_rect id=%s %s", ref_id, ser_rect);
145  if method != None:
146  self.templates[ref_id]['method'] = method
147  rospy.loginfo("set method id=%s method=%s", ref_id, method);
148 
149  def set_reference (self, rect):
150  if self.reference_image_msg == None: return
151  try:
152  cv_image = self.bridge.imgmsg_to_cv2(
153  self.reference_image_msg, "bgr8")
154  self.set_template('',ref_image=cv_image, ref_rect=rect)
155  except CvBridgeError as e:
156  print(e)
157 
158  #
159  # Callback Functions (lock require)
160  #
161 
162  # simple point tracking callback
163  def set_reference_point_callback (self, msg): # PointStamped
164  self.lockobj.acquire()
165  pt = (int(msg.point.x),int(msg.point.y))
166  rect = (pt[0]-int(self.default_template_size[0]/2),
167  pt[1]-int(self.default_template_size[1]/2),
169  self.set_reference(rect)
170  print(rect)
171  search_rect = (pt[0]-int(self.default_search_size[0]/2),
172  pt[1]-int(self.default_search_size[1]/2),
174  self.set_template('',ser_frame=None, ser_rect=search_rect)
175  self.lockobj.release()
176 
177  # store the latest image
178  def set_search_callback (self, msg):
179  self.lockobj.acquire()
180  self.set_template(ser_rect=(msg.x,msg.y,msg.width,msg.height))
181  self.lockobj.release()
182 
183  # store the latest image
184  def ref_image_callback (self, msg):
185  self.lockobj.acquire()
186  self.reference_image_msg = msg
187  self.lockobj.release()
188 
189  # reconfigure
190  def reconfigure(self,config,level):
191  self.lockobj.acquire()
192  # param
193  self.default_template_size = (config['default_template_width'],
194  config['default_template_height'])
195  self.default_search_size = (config['default_search_width'],
196  config['default_search_height'])
197  self.show_debug_image = config['show_debug_image']
198  self.auto_search_area = config['auto_search_area']
199 
200  if config['current_template_id'] in self.templates.keys():
201  # set template configuration
202  template = self.templates[config['current_template_id']]
203  method_enum = [
204  cv2.TM_SQDIFF, cv2.TM_SQDIFF_NORMED, cv2.TM_CCORR,
205  cv2.TM_CCORR_NORMED, cv2.TM_CCOEFF, cv2.TM_CCOEFF_NORMED]
206  if (template['ref_point'] is not None) and \
207  (template['ref_image'] is not None):
208  ref_pt = template['ref_point']
209  ref_size = template['ref_image'].shape
210  ref_rect = (ref_pt[0]-int(ref_size[0]/2),ref_pt[1]-int(ref_size[1]/2),ref_size[0],ref_size[1])
211  self.set_template(ref_id=config['current_template_id'],
212  color=config['template_color_space'],
213  ref_rect=ref_rect,
214  method=method_enum[config['match_method']])
215  # return current configuration
216  config['template_color_method'] = template['color']
217  self.lockobj.release()
218  return config
219 
220  def ser_image_callback (self, msg):
221  # initialize debug image
222  if self.show_debug_image:
223  debug_image = self.bridge.imgmsg_to_cv2(msg, "bgr8")
224 
225  self.lockobj.acquire()
226 
227  # match for each template
228  for template_id in self.templates.keys():
229  reference_image = self.templates[template_id]['ref_image']
230  search_rect = self.templates[template_id]['ser_rect']
231  matchmethod = self.templates[template_id]['method']
232  color_space = self.templates[template_id]['color']
233  if reference_image is None:
234  continue
235  if search_rect == None: continue
236  if (self.templates[template_id]['ser_frame'] != None and
237  self.templates[template_id]['ser_frame'] != msg.header.frame_id): continue
238 
239  # search rect &= image size
240  search_rect = (max(0,search_rect[0]),
241  max(0,search_rect[1]),
242  min(msg.width,search_rect[0]+search_rect[2])- max(0,search_rect[0]),
243  min(msg.height,search_rect[1]+search_rect[3])- max(0,search_rect[1]))
244 
245  result = TransformStamped(header=msg.header)
246 
247  try:
248  if color_space == 'mono8':
249  search_image = self.bridge.imgmsg_to_cv2(msg, 'mono8')
250  else:
251  search_image = self.bridge.imgmsg_to_cv2(msg, 'bgr8')
252  if color_space != 'bgr8':
253  search_image = cv2.cvtColor(
254  search_image, cv2.COLOR_BGR2HSV)
255 
256  image_size = search_image.shape
257  reference_size = (
258  reference_image.shape[1], reference_image.shape[0])
259 
260  # search size < reference size
261  if (search_rect[2] < reference_size[0]) or (search_rect[3] < reference_size[1]):
262  continue
263 
264  results = cv2.matchTemplate(
265  search_image[
266  search_rect[1]:search_rect[1] + search_rect[3],
267  search_rect[0]:search_rect[0] + search_rect[2]],
268  reference_image, matchmethod)
269 
270  if matchmethod in [cv2.TM_SQDIFF, cv2.TM_SQDIFF_NORMED]:
271  status = MinLock2nd(results,reference_size) # minimum for SSD
272  else:
273  status = MaxLock2nd(results,reference_size) # maximum for others
274  status = (1 - status[0], 1 - status[1], status[2], status[3])
275 
276  result_pt = (status[2][0]+search_rect[0]+int(reference_size[0]/2),
277  status[2][1]+search_rect[1]+int(reference_size[1]/2))
278 
279  # publish center position as result
280  result.child_frame_id = template_id
281  result.transform.translation.x = result_pt[0]
282  result.transform.translation.y = result_pt[1]
283  result.transform.rotation.w = 1 # not rotate, temporary
284  self.result_pub.publish(result)
285 
286  if reference_image.ndim == 2 and \
287  reference_image.dtype == np.uint8:
288  ref_msg = self.bridge.cv2_to_imgmsg(
289  reference_image, "mono8")
290  else:
291  ref_msg = self.bridge.cv2_to_imgmsg(
292  reference_image, "bgr8")
293  self.reference_pub.publish(ref_msg)
294 
295  # self feedback
296  if self.auto_search_area:
297  val_x = result_pt[0]-int(search_rect[2]/2)
298  val_y = result_pt[1]-int(search_rect[3]/2)
299  ser_scale = max(2,5+np.log(status[0])) # ???
300  new_ser_rect = (
301  min(max(val_x,0),image_size[0]-search_rect[2]),
302  min(max(val_y,0),image_size[1]-search_rect[3]),
303  reference_size[0]*ser_scale,reference_size[1]*ser_scale)
304  self.set_template(ser_rect=new_ser_rect)
305 
306  # draw on debug image
307  if self.show_debug_image:
308  cv2.rectangle(debug_image,
309  (result_pt[0] - int(reference_size[0]/2),
310  result_pt[1] - int(reference_size[1]/2)),
311  (result_pt[0] + int(reference_size[0]/2),
312  result_pt[1] + int(reference_size[1]/2)),
313  color=(0, 0, 255)) # red
314  cv2.rectangle(debug_image,
315  (search_rect[0], search_rect[1]),
316  (search_rect[0] + search_rect[2],
317  search_rect[1] + search_rect[3]),
318  color=(0, 255, 0))
319  cv2.putText(
320  debug_image, str(status[0]),
321  (search_rect[0], search_rect[1] + search_rect[3]),
322  fontFace=cv2.FONT_HERSHEY_SIMPLEX, fontScale=1,
323  color=(0, 255, 0), thickness=2,
324  lineType=16) # 16 means cv2.CV_AA
325 
326  if reference_image.ndim == 2:
327  reference_color_image = cv2.cvtColor(
328  reference_image, cv2.COLOR_GRAY2BGR)
329  debug_image[
330  :reference_size[1], :reference_size[0], :] = \
331  reference_color_image.copy()
332  else:
333  debug_image[
334  :reference_size[1], :reference_size[0], :] = \
335  reference_image.copy()
336 
337  except CvBridgeError as e:
338  print(e)
339 
340  self.lockobj.release()
341 
342  if self.show_debug_image:
343  # calc and print fps (30frame avg)
344  self.clock += [rospy.Time.now()]
345  if 30 <= len(self.clock):
346  fps = 30.0 / (self.clock[29]-self.clock[0]).to_sec()
347  cv2.putText(
348  debug_image, '%.1f fps' % fps, (msg.width - 150, 40),
349  fontFace=cv2.FONT_HERSHEY_SIMPLEX, fontScale=1,
350  color=(0, 0, 255), # red
351  thickness=2, lineType=16) # 16 means cv2.CV_AA
352  self.clock = self.clock[-30:]
353  # publish debug image
354  debug_msg = self.bridge.cv2_to_imgmsg(debug_image, "bgr8")
355  self.debug_pub.publish(debug_msg)
356 
357  return
358 
359 if __name__=='__main__':
360  rospy.init_node('match_template')
361 
362  obj = MepConverter()
363 
364 
365  rospy.loginfo("reference image %s, size %s", obj.reference_image_sub.resolved_name, obj.default_template_size)
366  rospy.loginfo(" search_image %s, size %s", obj.search_image_sub.resolved_name, obj.default_search_size)
367 
368  rospy.spin()
node_scripts.matchtemplate.MaxLock2nd
def MaxLock2nd(arr, ex_size)
Definition: matchtemplate.py:54
node_scripts.matchtemplate.MepConverter.result_pub
result_pub
Definition: matchtemplate.py:71
node_scripts.matchtemplate.MepConverter.set_reference
def set_reference(self, rect)
Definition: matchtemplate.py:149
ssd_train_dataset.int
int
Definition: ssd_train_dataset.py:175
ssd_train_dataset.str
str
Definition: ssd_train_dataset.py:178
node_scripts.matchtemplate.MepConverter.ref_image_callback
def ref_image_callback(self, msg)
Definition: matchtemplate.py:184
node_scripts.matchtemplate.MepConverter.server
server
Definition: matchtemplate.py:86
msg
node_scripts.matchtemplate.MepConverter.set_template
def set_template(self, ref_id='', ref_image=None, ref_rect=None, ser_frame=None, ser_rect=None, color=None, method=None)
Definition: matchtemplate.py:89
node_scripts.matchtemplate.MepConverter.reference_image_sub
reference_image_sub
Definition: matchtemplate.py:76
node_scripts.matchtemplate.MepConverter.reference_image_msg
reference_image_msg
Definition: matchtemplate.py:64
node_scripts.matchtemplate.MepConverter.__init__
def __init__(self)
Definition: matchtemplate.py:61
node_scripts.matchtemplate.MepConverter.templates
templates
Definition: matchtemplate.py:65
node_scripts.matchtemplate.MepConverter.auto_search_area
auto_search_area
Definition: matchtemplate.py:198
node_scripts.matchtemplate.MinLock2nd
def MinLock2nd(arr, ex_size)
Definition: matchtemplate.py:52
node_scripts.matchtemplate.MepConverter.set_reference_point_callback
def set_reference_point_callback(self, msg)
Definition: matchtemplate.py:163
node_scripts.matchtemplate.MepConverter.default_search_size
default_search_size
Definition: matchtemplate.py:195
node_scripts.matchtemplate.MepConverter.reconfigure
def reconfigure(self, config, level)
Definition: matchtemplate.py:190
node_scripts.matchtemplate.MepConverter
Definition: matchtemplate.py:58
node_scripts.matchtemplate.MepConverter.lockobj
lockobj
Definition: matchtemplate.py:62
node_scripts.matchtemplate.MepConverter.reference_point_sub
reference_point_sub
Definition: matchtemplate.py:80
node_scripts.matchtemplate.MepConverter.set_search_callback
def set_search_callback(self, msg)
Definition: matchtemplate.py:178
node_scripts.matchtemplate.MepConverter.ser_image_callback
def ser_image_callback(self, msg)
Definition: matchtemplate.py:220
node_scripts.matchtemplate.MepConverter.show_debug_image
show_debug_image
Definition: matchtemplate.py:197
node_scripts.matchtemplate.MepConverter.debug_pub
debug_pub
Definition: matchtemplate.py:73
node_scripts.matchtemplate._MinMaxLock2nd
def _MinMaxLock2nd(arr, ex_size, is_min)
Definition: matchtemplate.py:39
node_scripts.matchtemplate.MepConverter.search_image_sub
search_image_sub
Definition: matchtemplate.py:78
node_scripts.matchtemplate.MepConverter.reference_pub
reference_pub
Definition: matchtemplate.py:69
node_scripts.matchtemplate.MepConverter.search_sub
search_sub
Definition: matchtemplate.py:83
node_scripts.matchtemplate.MepConverter.clock
clock
Definition: matchtemplate.py:66
node_scripts.matchtemplate.MepConverter.bridge
bridge
Definition: matchtemplate.py:59
node_scripts.matchtemplate.MepConverter.default_template_size
default_template_size
Definition: matchtemplate.py:193


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17