Skip to content

Commit

Permalink
Merge branch 'pr_from_534o' into add_matching_template
Browse files Browse the repository at this point in the history
- Some PR #1 are adapted
  • Loading branch information
7675t committed Jul 18, 2017
2 parents 2e5f4fe + 905b3db commit 031cd1f
Show file tree
Hide file tree
Showing 5 changed files with 96 additions and 76 deletions.
4 changes: 1 addition & 3 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -159,7 +159,7 @@ opencv_apps_add_nodelet(discrete_fourier_transform discrete_fourier_transform/di
# ./tutorial_code/Histograms_Matching/calcHist_Demo.cpp
# ./tutorial_code/Histograms_Matching/compareHist_Demo.cpp
# ./tutorial_code/Histograms_Matching/EqualizeHist_Demo.cpp
# ./tutorial_code/Histograms_Matching/MatchTemplate_Demo.cpp
opencv_apps_add_nodelet(match_template match_template/match_template src/nodelet/match_template_nodelet.cpp) # ./tutorial_code/Histograms_Matching/MatchTemplate_Demo.cpp

# imagecodecs
# ./tutorial_code/imgcodecs/GDAL_IO/gdal-image.cpp
Expand Down Expand Up @@ -331,8 +331,6 @@ endif()
# https://github.com/opencv/opencv/blob/2.4/samples/cpp/video_homography.cpp
# https://github.com/opencv/opencv/blob/2.4/samples/cpp/videocapture_pvapi.cpp

opencv_apps_add_nodelet(match_template match_template/match_template src/nodelet/match_template_nodelet.cpp)

add_library(${PROJECT_NAME} SHARED
src/nodelet/nodelet.cpp
${_opencv_apps_nodelet_cppfiles}
Expand Down
20 changes: 9 additions & 11 deletions cfg/MatchTemplate.cfg
Original file line number Diff line number Diff line change
Expand Up @@ -37,17 +37,15 @@ PACKAGE='match_template'
from dynamic_reconfigure.parameter_generator_catkin import *

gen = ParameterGenerator()

method_enum = gen.enum([ gen.const("TM_SQDIFF", int_t, 0, "TM_SQDIFF"),
gen.const("TM_SQDIFF_NORMED", int_t, 1, "TM_SQDIFF_NORMED"),
gen.const("TM_CCORR", int_t, 2, "TM_CCORR"),
gen.const("TM_CCORR_NORMED", int_t, 3, "TM_CCORR_NORMED"),
gen.const("TM_CCOEFF", int_t, 4, "TM_CCOEFF"),
gen.const("TM_CCOEFF_NORMED", int_t, 5, "TM_CCOEFF_NORMED")],
"Template matching method")

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)
match_type = gen.enum([gen.const("CV_TM_SQDIFF", int_t, 0, "Sum of Ssquared Difference"),
gen.const("CV_TM_SQDIFF_NORMED", int_t, 1, "Sum of Normalized Ssquared Difference"),
gen.const("CV_TM_CCORR", int_t, 2, "Correlation"),
gen.const("CV_TM_CCORR_NORMED", int_t, 3, "Normalized Correlation"),
gen.const("CV_TM_CCOEFF", int_t, 4, "Correlation of Coefficient"),
gen.const("CV_TM_CCOEFF_NORMED", int_t, 5, "Normalized Correlation of Coefficient"),
], "An enum for Mathing Mehtods")
gen.add("match_method", int_t, 0, "Matching Methods", 5, 0, 5, edit_method=match_type)
gen.add("match_threshold", double_t, 0, "Matching Threshold", 0.0, 0.0, 1.0)

exit(gen.generate(PACKAGE, "match_template", "MatchTemplate"))
8 changes: 5 additions & 3 deletions launch/match_template.launch
Original file line number Diff line number Diff line change
Expand Up @@ -2,9 +2,10 @@
<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="true" doc="Specify whether the node displays a window to show edge image" />
<arg name="debug_view" default="false" 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" />
<arg name="template_file" default="$(find opencv_apps)/template.png" doc="filename for template image"/>
<arg name="mask_file" default="$(find opencv_apps)/mask.png" doc="filename for mask image"/>

<!-- match_template_nodelet.cpp -->
<node name="$(arg node_name)" pkg="opencv_apps" type="match_template" output="screen">
Expand All @@ -13,7 +14,8 @@
<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="$(arg template_file)"/>
<param name="template_file" value="$(arg template_file)" />
<param name="mask_file" value="$(arg mask_file)" />
<param name="match_threshold" value="0.0"/>
</node>
</launch>
105 changes: 69 additions & 36 deletions src/nodelet/match_template_nodelet.cpp
Original file line number Diff line number Diff line change
@@ -1,38 +1,50 @@
/*********************************************************************
* Software License Agreement (BSD License)
*
* Copyright (c) 2017, Ryosuke Tajima.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Ryosuke Tajima nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/
* Software License Agreement (BSD License)
*
* Copyright (c) 2017, Ryosuke Tajima.
* All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* * Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* * Redistributions in binary form must reproduce the above
* copyright notice, this list of conditions and the following
* disclaimer in the documentation and/or other materials provided
* with the distribution.
* * Neither the name of the Ryosuke Tajima nor the names of its
* contributors may be used to endorse or promote products derived
* from this software without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
* LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
* CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*********************************************************************/

// https://github.com/opencv/opencv/raw/master/samples/cpp/tutorial_code/Histograms_Matching/MatchTemplate_Demo.cpp
/**
* @file MatchTemplate_Demo.cpp
* @brief Sample code to use the function MatchTemplate
* @author OpenCV team
*/

#include <ros/ros.h>
#include "opencv_apps/nodelet.h"
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>

#include <opencv2/highgui/highgui.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/imgproc/types_c.h>
Expand Down Expand Up @@ -70,6 +82,11 @@ class MatchTemplateNodelet:public opencv_apps::Nodelet
bool debug_view_;
ros::Time prev_stamp_;
cv::Mat templ_;
// mask is only supported since opencv 3.2 (https://github.com/opencv/opencv/pull/3554)
#if (CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 2)
bool use_mask_;
cv::Mat mask_;
#endif

std::string scene_window_name_, templ_window_name_;
static bool mouse_update_;
Expand Down Expand Up @@ -164,7 +181,17 @@ class MatchTemplateNodelet:public opencv_apps::Nodelet
mouse_update_ = false;
}
// Match template
matchTemplate (frame, templ_, score, config_.match_method);
bool method_accepts_mask = (config_.match_method == CV_TM_SQDIFF || config_.match_method == CV_TM_CCORR_NORMED);
#if (CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 2)
if (use_mask_ && method_accepts_mask)
{
matchTemplate (frame, templ_, score, config_.match_method, mask_);
}
else
#endif
{
matchTemplate (frame, templ_, score, config_.match_method);
}
/// Localizing the best match with minMaxLoc
int remove_margin_x = templ_.cols / 2;
int remove_margin_y = templ_.rows / 2;
Expand Down Expand Up @@ -290,10 +317,16 @@ class MatchTemplateNodelet:public opencv_apps::Nodelet
pnh_->param ("template_file", templ_file, std::string (""));
if (!templ_file.empty())
{
NODELET_INFO ("template_file: %s\n", templ_file.c_str());
templ_ = imread (templ_file, cv::IMREAD_COLOR);
}

#if (CV_MAJOR_VERSION >= 3 && CV_MINOR_VERSION >= 2)
std::string mask_file;
pnh_->param ("mask_file", mask_file, std::string ("mask.png"));
if (use_mask_)
{
mask_ = imread (mask_file, cv::IMREAD_COLOR);
}
#endif
if (debug_view_)
{
always_subscribe_ = true;
Expand All @@ -310,6 +343,7 @@ class MatchTemplateNodelet:public opencv_apps::Nodelet
reconfigure_server_->setCallback (f);

scene_img_pub_ = advertiseImage (*pnh_, "image", 1);
// template is global topic, so mouse selection publish it globaly.
templ_img_pub_ = advertiseImage (*nh_, "template", 1);
score_img_pub_ = advertiseImage (*pnh_, "score_image", 1);
msg_pub_ = advertise < geometry_msgs::PointStamped > (*pnh_, "pixel_position", 1);
Expand All @@ -318,7 +352,6 @@ class MatchTemplateNodelet:public opencv_apps::Nodelet
onInitPostProcess ();
}
};
// bool MatchTemplateNodelet::need_config_update_ = false;
bool MatchTemplateNodelet::mouse_update_ = false;
int MatchTemplateNodelet::mouse_event_ = 0;
int MatchTemplateNodelet::mouse_x_ = 0;
Expand Down
35 changes: 12 additions & 23 deletions test/test-match_template.test
Original file line number Diff line number Diff line change
@@ -1,44 +1,33 @@
<launch>
<arg name="gui" default="true" />
<arg name="use_opencv3" default="false" />
<arg name="use_opencv3_1" default="false" />
<arg name="use_opencv3_2" default="false" />
<node name="play_face_bag" pkg="rosbag" type="play" args="-l $(find opencv_apps)/test/face_detector_withface_test_diamondback.bag" />

<group ns="wide_stereo/left" >
<node name="image_proc" pkg="image_proc" type="image_proc" />
<node name="image_view" pkg="image_view" type="image_view" args="image:=image_rect" if="$(arg gui)" />
<!-- match_template.cpp -->
<node name="image_view" pkg="image_view" type="image_view" args="image:=image_rect_color" if="$(arg gui)" />

<!-- convex_hull.cpp -->
<include file="$(find opencv_apps)/launch/match_template.launch" >
<arg name="debug_view" value="$(arg gui)" />
<arg name="image" value="image_raw" />
<arg name="template_file" value="$(find opencv_apps)/test/template.png"/>
<!--
<arg name="use_opencv3" value="$(arg use_opencv3)" />
<arg name="use_opencv3_1" value="$(arg use_opencv3_1)" />
<arg name="use_opencv3_2" value="$(arg use_opencv3_2)" />
-->
<arg name="image" value="image_rect" />
<arg name="template_file" value="$(find opencv_apps)/test/template.png" />
<arg name="mask_file" value="" />
</include>

<!-- Test Codes -->
<node name="scene_saver" pkg="image_view" type="image_saver">
<remap from="image" to="match_template/image" />
<param name="filename_format" value="$(find opencv_apps)/test/matched_scene.png"/>
</node>
<node name="template_saver" pkg="image_view" type="image_saver">
<remap from="image" to="match_template/template" />
<param name="filename_format" value="$(find opencv_apps)/test/matched_template.png" />
<node name="match_template_saver" pkg="image_view" type="image_saver" args="image:=match_template/image" >
<param name="filename_format" value="$(find opencv_apps)/test/match_template.png"/>
</node>
<param name="image_test/topic" value="match_template/image" />
<test test-name="image_test" pkg="rostest" type="hztest" name="image_test" >
<param name="hz" value="16" />
<param name="hzerror" value="14" />
<param name="hz" value="20" />
<param name="hzerror" value="15" />
<param name="test_duration" value="5.0" />
</test>
<param name="score_image_test/topic" value="match_template/score_image" />
<test test-name="score_image_test" pkg="rostest" type="hztest" name="score_image_test" >
<param name="hz" value="16" />
<param name="hzerror" value="14" />
<param name="hz" value="20" />
<param name="hzerror" value="15" />
<param name="test_duration" value="5.0" />
</test>
</group>
Expand Down

0 comments on commit 031cd1f

Please sign in to comment.