Skip to content

Commit 2e5f4fe

Browse files
committed
Add rostest for match_template
- Test using face_detector_withface_test_diamondback.bag - Dynamic reconfigure for match_threshold - Chnage to match only one in the scene image - Change to use camera_info to publish gaze_vector
1 parent 9cbfdfc commit 2e5f4fe

File tree

7 files changed

+331
-250
lines changed

7 files changed

+331
-250
lines changed

CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
cmake_minimum_required(VERSION 2.8.3)
22
project(opencv_apps)
33

4-
find_package(catkin REQUIRED COMPONENTS cv_bridge dynamic_reconfigure message_generation image_transport nodelet roscpp sensor_msgs)
4+
find_package(catkin REQUIRED COMPONENTS cv_bridge dynamic_reconfigure message_generation image_transport image_geometry nodelet roscpp sensor_msgs)
55

66
find_package(OpenCV REQUIRED)
77
message(STATUS "OpenCV VERSION: ${OpenCV_VERSION}")

cfg/MatchTemplate.cfg

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -48,5 +48,6 @@ method_enum = gen.enum([ gen.const("TM_SQDIFF", int_t, 0, "TM_SQDIFF"),
4848

4949
gen.add("match_method", int_t, 0, "Template matching method", 5, 0, 5, edit_method=method_enum)
5050
gen.add("use_camera_info", bool_t, 0, "Indicates that the camera_info topic should be subscribed to to get the default input_frame_id. Otherwise the frame from the image message will be used.", False)
51+
gen.add("match_threshold", double_t, 0, "Template matching threshold", 0.0, 0.0, 1.0)
5152

5253
exit(gen.generate(PACKAGE, "match_template", "MatchTemplate"))

launch/match_template.launch

Lines changed: 5 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -2,8 +2,9 @@
22
<arg name="node_name" default="match_template" />
33
<arg name="image" default="image" doc="The image topic. Should be remapped to the name of the real image topic." />
44
<arg name="use_camera_info" default="false" doc="Indicates that the camera_info topic should be subscribed to to get the default input_frame_id. Otherwise the frame from the image message will be used." />
5-
<arg name="debug_view" default="false" doc="Specify whether the node displays a window to show edge image" />
6-
<arg name="match_method" default="0" doc="Matching method. 0:CV_TM_SQDIFF 1:CV_TM_SQDIFF_NORMED 2:CV_TM_CCORR 3:CV_TM_CCORR_NORMED 4:CV_TM_CCOEFF 5:CV_TM_CCOEFF_NORMED" />
5+
<arg name="debug_view" default="true" doc="Specify whether the node displays a window to show edge image" />
6+
<arg name="match_method" default="5" doc="Matching method. 0:CV_TM_SQDIFF 1:CV_TM_SQDIFF_NORMED 2:CV_TM_CCORR 3:CV_TM_CCORR_NORMED 4:CV_TM_CCOEFF 5:CV_TM_CCOEFF_NORMED" />
7+
<arg name="template_file" default="" doc="Template file to use" />
78

89
<!-- match_template_nodelet.cpp -->
910
<node name="$(arg node_name)" pkg="opencv_apps" type="match_template" output="screen">
@@ -12,7 +13,7 @@
1213
<param name="debug_view" value="$(arg debug_view)" />
1314
<param name="match_method" value="$(arg match_method)" />
1415
<param name="use_mask" value="false" />
15-
<param name="template_file" value="$(find opencv_apps)/template.png" />
16-
<param name="mask_file" value="$(find opencv_apps)/mask.png" />
16+
<param name="template_file" value="$(arg template_file)"/>
17+
<param name="match_threshold" value="0.0"/>
1718
</node>
1819
</launch>

0 commit comments

Comments
 (0)