3 import roslib; roslib.load_manifest(
'jsk_perception')
9 import _thread
as thread
10 from sensor_msgs.msg
import Image
12 from jsk_recognition_msgs.msg
import Rect
14 from cv_bridge
import CvBridge, CvBridgeError
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
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])
70 "current_template", Image, queue_size=1)
72 "result", TransformStamped, queue_size=1)
73 self.
debug_pub = rospy.Publisher(
"debug_image", Image, queue_size=1)
81 rospy.resolve_name(
"set_reference_point"),
83 self.
search_sub = rospy.Subscriber(rospy.resolve_name(
"set_search_rect"),
90 ser_frame=None, ser_rect=None, color=None, method=None):
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}
97 color_changed = (self.
templates[ref_id][
'color'] != color)
and (color !=
None)
99 something_changed = (ref_image
is not None)
or \
100 (ref_rect
is not None)
or color_changed
103 if ref_image
is not None:
104 self.
templates[ref_id][
'ref_orig'] = ref_image.copy()
106 ref_image = self.
templates[ref_id][
'ref_orig']
109 if ref_image
is not None and ref_image.ndim == 2:
116 if (ref_rect
is not None)
and (ref_image
is not None)
and \
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)
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);
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);
143 self.
templates[ref_id][
'ser_rect'] = ser_rect
146 self.
templates[ref_id][
'method'] = method
147 rospy.loginfo(
"set method id=%s method=%s", ref_id, method);
152 cv_image = self.
bridge.imgmsg_to_cv2(
155 except CvBridgeError
as e:
165 pt = (
int(msg.point.x),
int(msg.point.y))
174 self.
set_template(
'',ser_frame=
None, ser_rect=search_rect)
180 self.
set_template(ser_rect=(msg.x,msg.y,msg.width,msg.height))
194 config[
'default_template_height'])
196 config[
'default_search_height'])
200 if config[
'current_template_id']
in self.
templates.keys():
202 template = self.
templates[config[
'current_template_id']]
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])
212 color=config[
'template_color_space'],
214 method=method_enum[config[
'match_method']])
216 config[
'template_color_method'] = template[
'color']
223 debug_image = self.
bridge.imgmsg_to_cv2(msg,
"bgr8")
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:
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
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]))
245 result = TransformStamped(header=msg.header)
248 if color_space ==
'mono8':
249 search_image = self.
bridge.imgmsg_to_cv2(msg,
'mono8')
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)
256 image_size = search_image.shape
258 reference_image.shape[1], reference_image.shape[0])
261 if (search_rect[2] < reference_size[0])
or (search_rect[3] < reference_size[1]):
264 results = cv2.matchTemplate(
266 search_rect[1]:search_rect[1] + search_rect[3],
267 search_rect[0]:search_rect[0] + search_rect[2]],
268 reference_image, matchmethod)
270 if matchmethod
in [cv2.TM_SQDIFF, cv2.TM_SQDIFF_NORMED]:
274 status = (1 - status[0], 1 - status[1], status[2], status[3])
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))
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
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")
291 ref_msg = self.
bridge.cv2_to_imgmsg(
292 reference_image,
"bgr8")
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]))
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)
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)),
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]),
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,
326 if reference_image.ndim == 2:
327 reference_color_image = cv2.cvtColor(
328 reference_image, cv2.COLOR_GRAY2BGR)
330 :reference_size[1], :reference_size[0], :] = \
331 reference_color_image.copy()
334 :reference_size[1], :reference_size[0], :] = \
335 reference_image.copy()
337 except CvBridgeError
as e:
344 self.
clock += [rospy.Time.now()]
345 if 30 <= len(self.
clock):
346 fps = 30.0 / (self.
clock[29]-self.
clock[0]).to_sec()
348 debug_image,
'%.1f fps' % fps, (msg.width - 150, 40),
349 fontFace=cv2.FONT_HERSHEY_SIMPLEX, fontScale=1,
351 thickness=2, lineType=16)
354 debug_msg = self.
bridge.cv2_to_imgmsg(debug_image,
"bgr8")
359 if __name__==
'__main__':
360 rospy.init_node(
'match_template')
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)