Skip to content

Commit

Permalink
Add rostest for match_template
Browse files Browse the repository at this point in the history
- 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
  • Loading branch information
7675t committed Jul 18, 2017
1 parent 9cbfdfc commit 2e5f4fe
Show file tree
Hide file tree
Showing 7 changed files with 331 additions and 250 deletions.
2 changes: 1 addition & 1 deletion CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
cmake_minimum_required(VERSION 2.8.3)
project(opencv_apps)

find_package(catkin REQUIRED COMPONENTS cv_bridge dynamic_reconfigure message_generation image_transport nodelet roscpp sensor_msgs)
find_package(catkin REQUIRED COMPONENTS cv_bridge dynamic_reconfigure message_generation image_transport image_geometry nodelet roscpp sensor_msgs)

find_package(OpenCV REQUIRED)
message(STATUS "OpenCV VERSION: ${OpenCV_VERSION}")
Expand Down
1 change: 1 addition & 0 deletions cfg/MatchTemplate.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -48,5 +48,6 @@ method_enum = gen.enum([ gen.const("TM_SQDIFF", int_t, 0, "TM_SQDIFF"),

gen.add("match_method", int_t, 0, "Template matching method", 5, 0, 5, edit_method=method_enum)
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)
gen.add("match_threshold", double_t, 0, "Template matching threshold", 0.0, 0.0, 1.0)

exit(gen.generate(PACKAGE, "match_template", "MatchTemplate"))
9 changes: 5 additions & 4 deletions launch/match_template.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,8 +2,9 @@
<arg name="node_name" default="match_template" />
<arg name="image" default="image" doc="The image topic. Should be remapped to the name of the real image topic." />
<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." />
<arg name="debug_view" default="false" doc="Specify whether the node displays a window to show edge image" />
<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" />
<arg name="debug_view" default="true" doc="Specify whether the node displays a window to show edge image" />
<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" />
<arg name="template_file" default="" doc="Template file to use" />

<!-- match_template_nodelet.cpp -->
<node name="$(arg node_name)" pkg="opencv_apps" type="match_template" output="screen">
Expand All @@ -12,7 +13,7 @@
<param name="debug_view" value="$(arg debug_view)" />
<param name="match_method" value="$(arg match_method)" />
<param name="use_mask" value="false" />
<param name="template_file" value="$(find opencv_apps)/template.png" />
<param name="mask_file" value="$(find opencv_apps)/mask.png" />
<param name="template_file" value="$(arg template_file)"/>
<param name="match_threshold" value="0.0"/>
</node>
</launch>
Loading

0 comments on commit 2e5f4fe

Please sign in to comment.