Skip to content

Commit 031cd1f

Browse files
committed
Merge branch 'pr_from_534o' into add_matching_template
- Some PR #1 are adapted
2 parents 2e5f4fe + 905b3db commit 031cd1f

File tree

5 files changed

+96
-76
lines changed

5 files changed

+96
-76
lines changed

CMakeLists.txt

Lines changed: 1 addition & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -159,7 +159,7 @@ opencv_apps_add_nodelet(discrete_fourier_transform discrete_fourier_transform/di
159159
# ./tutorial_code/Histograms_Matching/calcHist_Demo.cpp
160160
# ./tutorial_code/Histograms_Matching/compareHist_Demo.cpp
161161
# ./tutorial_code/Histograms_Matching/EqualizeHist_Demo.cpp
162-
# ./tutorial_code/Histograms_Matching/MatchTemplate_Demo.cpp
162+
opencv_apps_add_nodelet(match_template match_template/match_template src/nodelet/match_template_nodelet.cpp) # ./tutorial_code/Histograms_Matching/MatchTemplate_Demo.cpp
163163

164164
# imagecodecs
165165
# ./tutorial_code/imgcodecs/GDAL_IO/gdal-image.cpp
@@ -331,8 +331,6 @@ endif()
331331
# https://github.com/opencv/opencv/blob/2.4/samples/cpp/video_homography.cpp
332332
# https://github.com/opencv/opencv/blob/2.4/samples/cpp/videocapture_pvapi.cpp
333333

334-
opencv_apps_add_nodelet(match_template match_template/match_template src/nodelet/match_template_nodelet.cpp)
335-
336334
add_library(${PROJECT_NAME} SHARED
337335
src/nodelet/nodelet.cpp
338336
${_opencv_apps_nodelet_cppfiles}

cfg/MatchTemplate.cfg

Lines changed: 9 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -37,17 +37,15 @@ PACKAGE='match_template'
3737
from dynamic_reconfigure.parameter_generator_catkin import *
3838

3939
gen = ParameterGenerator()
40-
41-
method_enum = gen.enum([ gen.const("TM_SQDIFF", int_t, 0, "TM_SQDIFF"),
42-
gen.const("TM_SQDIFF_NORMED", int_t, 1, "TM_SQDIFF_NORMED"),
43-
gen.const("TM_CCORR", int_t, 2, "TM_CCORR"),
44-
gen.const("TM_CCORR_NORMED", int_t, 3, "TM_CCORR_NORMED"),
45-
gen.const("TM_CCOEFF", int_t, 4, "TM_CCOEFF"),
46-
gen.const("TM_CCOEFF_NORMED", int_t, 5, "TM_CCOEFF_NORMED")],
47-
"Template matching method")
48-
49-
gen.add("match_method", int_t, 0, "Template matching method", 5, 0, 5, edit_method=method_enum)
5040
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)
41+
match_type = gen.enum([gen.const("CV_TM_SQDIFF", int_t, 0, "Sum of Ssquared Difference"),
42+
gen.const("CV_TM_SQDIFF_NORMED", int_t, 1, "Sum of Normalized Ssquared Difference"),
43+
gen.const("CV_TM_CCORR", int_t, 2, "Correlation"),
44+
gen.const("CV_TM_CCORR_NORMED", int_t, 3, "Normalized Correlation"),
45+
gen.const("CV_TM_CCOEFF", int_t, 4, "Correlation of Coefficient"),
46+
gen.const("CV_TM_CCOEFF_NORMED", int_t, 5, "Normalized Correlation of Coefficient"),
47+
], "An enum for Mathing Mehtods")
48+
gen.add("match_method", int_t, 0, "Matching Methods", 5, 0, 5, edit_method=match_type)
49+
gen.add("match_threshold", double_t, 0, "Matching Threshold", 0.0, 0.0, 1.0)
5250

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

launch/match_template.launch

Lines changed: 5 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -2,9 +2,10 @@
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="true" doc="Specify whether the node displays a window to show edge image" />
5+
<arg name="debug_view" default="false" doc="Specify whether the node displays a window to show edge image" />
66
<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" />
7+
<arg name="template_file" default="$(find opencv_apps)/template.png" doc="filename for template image"/>
8+
<arg name="mask_file" default="$(find opencv_apps)/mask.png" doc="filename for mask image"/>
89

910
<!-- match_template_nodelet.cpp -->
1011
<node name="$(arg node_name)" pkg="opencv_apps" type="match_template" output="screen">
@@ -13,7 +14,8 @@
1314
<param name="debug_view" value="$(arg debug_view)" />
1415
<param name="match_method" value="$(arg match_method)" />
1516
<param name="use_mask" value="false" />
16-
<param name="template_file" value="$(arg template_file)"/>
17+
<param name="template_file" value="$(arg template_file)" />
18+
<param name="mask_file" value="$(arg mask_file)" />
1719
<param name="match_threshold" value="0.0"/>
1820
</node>
1921
</launch>

src/nodelet/match_template_nodelet.cpp

Lines changed: 69 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -1,38 +1,50 @@
11
/*********************************************************************
2-
* Software License Agreement (BSD License)
3-
*
4-
* Copyright (c) 2017, Ryosuke Tajima.
5-
* All rights reserved.
6-
*
7-
* Redistribution and use in source and binary forms, with or without
8-
* modification, are permitted provided that the following conditions
9-
* are met:
10-
*
11-
* * Redistributions of source code must retain the above copyright
12-
* notice, this list of conditions and the following disclaimer.
13-
* * Redistributions in binary form must reproduce the above
14-
* copyright notice, this list of conditions and the following
15-
* disclaimer in the documentation and/or other materials provided
16-
* with the distribution.
17-
* * Neither the name of the Ryosuke Tajima nor the names of its
18-
* contributors may be used to endorse or promote products derived
19-
* from this software without specific prior written permission.
20-
*
21-
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22-
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23-
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24-
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25-
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26-
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27-
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28-
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29-
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30-
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31-
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32-
* POSSIBILITY OF SUCH DAMAGE.
33-
*********************************************************************/
2+
* Software License Agreement (BSD License)
3+
*
4+
* Copyright (c) 2017, Ryosuke Tajima.
5+
* All rights reserved.
6+
*
7+
* Redistribution and use in source and binary forms, with or without
8+
* modification, are permitted provided that the following conditions
9+
* are met:
10+
*
11+
* * Redistributions of source code must retain the above copyright
12+
* notice, this list of conditions and the following disclaimer.
13+
* * Redistributions in binary form must reproduce the above
14+
* copyright notice, this list of conditions and the following
15+
* disclaimer in the documentation and/or other materials provided
16+
* with the distribution.
17+
* * Neither the name of the Ryosuke Tajima nor the names of its
18+
* contributors may be used to endorse or promote products derived
19+
* from this software without specific prior written permission.
20+
*
21+
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22+
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23+
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24+
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25+
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26+
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27+
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28+
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29+
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30+
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31+
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32+
* POSSIBILITY OF SUCH DAMAGE.
33+
*********************************************************************/
3434

3535
// https://github.com/opencv/opencv/raw/master/samples/cpp/tutorial_code/Histograms_Matching/MatchTemplate_Demo.cpp
36+
/**
37+
* @file MatchTemplate_Demo.cpp
38+
* @brief Sample code to use the function MatchTemplate
39+
* @author OpenCV team
40+
*/
41+
42+
#include <ros/ros.h>
43+
#include "opencv_apps/nodelet.h"
44+
#include <image_transport/image_transport.h>
45+
#include <cv_bridge/cv_bridge.h>
46+
#include <sensor_msgs/image_encodings.h>
47+
3648
#include <opencv2/highgui/highgui.hpp>
3749
#include <opencv2/imgproc/imgproc.hpp>
3850
#include <opencv2/imgproc/types_c.h>
@@ -70,6 +82,11 @@ class MatchTemplateNodelet:public opencv_apps::Nodelet
7082
bool debug_view_;
7183
ros::Time prev_stamp_;
7284
cv::Mat templ_;
85+
// mask is only supported since opencv 3.2 (https://github.com/opencv/opencv/pull/3554)
86+
#if (CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 2)
87+
bool use_mask_;
88+
cv::Mat mask_;
89+
#endif
7390

7491
std::string scene_window_name_, templ_window_name_;
7592
static bool mouse_update_;
@@ -164,7 +181,17 @@ class MatchTemplateNodelet:public opencv_apps::Nodelet
164181
mouse_update_ = false;
165182
}
166183
// Match template
167-
matchTemplate (frame, templ_, score, config_.match_method);
184+
bool method_accepts_mask = (config_.match_method == CV_TM_SQDIFF || config_.match_method == CV_TM_CCORR_NORMED);
185+
#if (CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 2)
186+
if (use_mask_ && method_accepts_mask)
187+
{
188+
matchTemplate (frame, templ_, score, config_.match_method, mask_);
189+
}
190+
else
191+
#endif
192+
{
193+
matchTemplate (frame, templ_, score, config_.match_method);
194+
}
168195
/// Localizing the best match with minMaxLoc
169196
int remove_margin_x = templ_.cols / 2;
170197
int remove_margin_y = templ_.rows / 2;
@@ -290,10 +317,16 @@ class MatchTemplateNodelet:public opencv_apps::Nodelet
290317
pnh_->param ("template_file", templ_file, std::string (""));
291318
if (!templ_file.empty())
292319
{
293-
NODELET_INFO ("template_file: %s\n", templ_file.c_str());
294320
templ_ = imread (templ_file, cv::IMREAD_COLOR);
295321
}
296-
322+
#if (CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 2)
323+
std::string mask_file;
324+
pnh_->param ("mask_file", mask_file, std::string ("mask.png"));
325+
if (use_mask_)
326+
{
327+
mask_ = imread (mask_file, cv::IMREAD_COLOR);
328+
}
329+
#endif
297330
if (debug_view_)
298331
{
299332
always_subscribe_ = true;
@@ -310,6 +343,7 @@ class MatchTemplateNodelet:public opencv_apps::Nodelet
310343
reconfigure_server_->setCallback (f);
311344

312345
scene_img_pub_ = advertiseImage (*pnh_, "image", 1);
346+
// template is global topic, so mouse selection publish it globaly.
313347
templ_img_pub_ = advertiseImage (*nh_, "template", 1);
314348
score_img_pub_ = advertiseImage (*pnh_, "score_image", 1);
315349
msg_pub_ = advertise < geometry_msgs::PointStamped > (*pnh_, "pixel_position", 1);
@@ -318,7 +352,6 @@ class MatchTemplateNodelet:public opencv_apps::Nodelet
318352
onInitPostProcess ();
319353
}
320354
};
321-
// bool MatchTemplateNodelet::need_config_update_ = false;
322355
bool MatchTemplateNodelet::mouse_update_ = false;
323356
int MatchTemplateNodelet::mouse_event_ = 0;
324357
int MatchTemplateNodelet::mouse_x_ = 0;

test/test-match_template.test

Lines changed: 12 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -1,44 +1,33 @@
11
<launch>
22
<arg name="gui" default="true" />
3-
<arg name="use_opencv3" default="false" />
4-
<arg name="use_opencv3_1" default="false" />
5-
<arg name="use_opencv3_2" default="false" />
63
<node name="play_face_bag" pkg="rosbag" type="play" args="-l $(find opencv_apps)/test/face_detector_withface_test_diamondback.bag" />
74

85
<group ns="wide_stereo/left" >
96
<node name="image_proc" pkg="image_proc" type="image_proc" />
10-
<node name="image_view" pkg="image_view" type="image_view" args="image:=image_rect" if="$(arg gui)" />
11-
<!-- match_template.cpp -->
7+
<node name="image_view" pkg="image_view" type="image_view" args="image:=image_rect_color" if="$(arg gui)" />
8+
9+
<!-- convex_hull.cpp -->
1210
<include file="$(find opencv_apps)/launch/match_template.launch" >
1311
<arg name="debug_view" value="$(arg gui)" />
14-
<arg name="image" value="image_raw" />
15-
<arg name="template_file" value="$(find opencv_apps)/test/template.png"/>
16-
<!--
17-
<arg name="use_opencv3" value="$(arg use_opencv3)" />
18-
<arg name="use_opencv3_1" value="$(arg use_opencv3_1)" />
19-
<arg name="use_opencv3_2" value="$(arg use_opencv3_2)" />
20-
-->
12+
<arg name="image" value="image_rect" />
13+
<arg name="template_file" value="$(find opencv_apps)/test/template.png" />
14+
<arg name="mask_file" value="" />
2115
</include>
2216

2317
<!-- Test Codes -->
24-
<node name="scene_saver" pkg="image_view" type="image_saver">
25-
<remap from="image" to="match_template/image" />
26-
<param name="filename_format" value="$(find opencv_apps)/test/matched_scene.png"/>
27-
</node>
28-
<node name="template_saver" pkg="image_view" type="image_saver">
29-
<remap from="image" to="match_template/template" />
30-
<param name="filename_format" value="$(find opencv_apps)/test/matched_template.png" />
18+
<node name="match_template_saver" pkg="image_view" type="image_saver" args="image:=match_template/image" >
19+
<param name="filename_format" value="$(find opencv_apps)/test/match_template.png"/>
3120
</node>
3221
<param name="image_test/topic" value="match_template/image" />
3322
<test test-name="image_test" pkg="rostest" type="hztest" name="image_test" >
34-
<param name="hz" value="16" />
35-
<param name="hzerror" value="14" />
23+
<param name="hz" value="20" />
24+
<param name="hzerror" value="15" />
3625
<param name="test_duration" value="5.0" />
3726
</test>
3827
<param name="score_image_test/topic" value="match_template/score_image" />
3928
<test test-name="score_image_test" pkg="rostest" type="hztest" name="score_image_test" >
40-
<param name="hz" value="16" />
41-
<param name="hzerror" value="14" />
29+
<param name="hz" value="20" />
30+
<param name="hzerror" value="15" />
4231
<param name="test_duration" value="5.0" />
4332
</test>
4433
</group>

0 commit comments

Comments
 (0)