diff --git a/CMakeLists.txt b/CMakeLists.txt index e4f8f6ff..af543659 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -52,6 +52,7 @@ generate_dynamic_reconfigure_options( cfg/GoodfeatureTrack.cfg cfg/CornerHarris.cfg # + cfg/CompareHistogram.cfg cfg/EqualizeHistogram.cfg cfg/CamShift.cfg cfg/FBackFlow.cfg @@ -169,8 +170,10 @@ opencv_apps_add_nodelet(discrete_fourier_transform src/nodelet/discrete_fourier_ # ./tutorial_code/Histograms_Matching/calcBackProject_Demo1.cpp # ./tutorial_code/Histograms_Matching/calcBackProject_Demo2.cpp # ./tutorial_code/Histograms_Matching/calcHist_Demo.cpp - # ./tutorial_code/Histograms_Matching/compareHist_Demo.cpp - opencv_apps_add_nodelet(equalize_histogram src/nodelet/equalize_histogram_nodelet.cpp) # ./tutorial_code/Histograms_Matching/EqualizeHist_Demo.cpp +if(OpenCV_VERSION VERSION_GREATER "3.0") + opencv_apps_add_nodelet(compare_histogram src/nodelet/compare_histogram_nodelet.cpp) # ./tutorial_code/Histograms_Matching/compareHist_Demo.cpp +endif() +opencv_apps_add_nodelet(equalize_histogram src/nodelet/equalize_histogram_nodelet.cpp) # ./tutorial_code/Histograms_Matching/EqualizeHist_Demo.cpp # ./tutorial_code/Histograms_Matching/MatchTemplate_Demo.cpp # imagecodecs @@ -387,6 +390,9 @@ if(CATKIN_ENABLE_TESTING) message(WARNING "roslaunch_add_file check fails with unsupported doc attributes ${roslaunch_VERSION}") else() file(GLOB LAUNCH_FILES launch/*.launch) + if(NOT OpenCV_VERSION VERSION_GREATER "3.0") + list(REMOVE_ITEM LAUNCH_FILES ${CMAKE_CURRENT_SOURCE_DIR}/launch/compare_histogram.launch) + endif() foreach(LAUNCH_FILE ${LAUNCH_FILES}) roslaunch_add_file_check(${LAUNCH_FILE}) endforeach() diff --git a/cfg/CompareHistogram.cfg b/cfg/CompareHistogram.cfg new file mode 100755 index 00000000..769ffc72 --- /dev/null +++ b/cfg/CompareHistogram.cfg @@ -0,0 +1,53 @@ +#! /usr/bin/env python +# Software License Agreement (BSD License) +# +# Copyright (c) 2022, Kei Okada +# 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 Kei Okada 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. + + +PACKAGE = "opencv_apps" + +from dynamic_reconfigure.parameter_generator_catkin import * + +gen = ParameterGenerator() +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) + +histogram_comparison_type = gen.enum([ gen.const("Correlation", int_t, 0, "Correlation"), + gen.const("Chi_Square", int_t, 1, "Chi-Square"), + gen.const("Intersection", int_t, 2, "Intersection"), + gen.const("Bhattacharyya", int_t, 3, "Bhattacharyya distance")], + "Histogram Comparison method") +gen.add("histogram_comparison_type", int_t, 1, "Histogram Comparison method", 0, 0, 3, edit_method=histogram_comparison_type) + +gen.add("histogram_size", int_t, 2, "Array of histogram sizes in each dimension", 256, 1, 1024) +gen.add("uniform", bool_t, 3, "Flag indicating whether the histogram is uniform or not", True) +gen.add("accumulate", bool_t, 4, "Accumulation flag. If it is set, the histogram is not cleared in the beginning when it is allocated", False) + +exit(gen.generate(PACKAGE, "compare_histogram", "CompareHistogram")) diff --git a/launch/compare_histogram.launch b/launch/compare_histogram.launch new file mode 100644 index 00000000..3b729369 --- /dev/null +++ b/launch/compare_histogram.launch @@ -0,0 +1,22 @@ + + + + + + + + + + + + + + + + + + + $(arg reference_histogram) + + + diff --git a/nodelet_plugins.xml b/nodelet_plugins.xml index 62f76e3d..430ac892 100644 --- a/nodelet_plugins.xml +++ b/nodelet_plugins.xml @@ -123,6 +123,10 @@ Nodelet to demonstrate the famous watershed segmentation algorithm in OpenCV: watershed() + + Nodelet of compare histogram + + Nodelet for histogram equalization diff --git a/src/nodelet/compare_histogram_nodelet.cpp b/src/nodelet/compare_histogram_nodelet.cpp new file mode 100644 index 00000000..e862f0f1 --- /dev/null +++ b/src/nodelet/compare_histogram_nodelet.cpp @@ -0,0 +1,299 @@ +/********************************************************************* +* Software License Agreement (BSD License) +* +* Copyright (c) 2020, Gaël Écorchard, Czech Technical University. +* 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 Gaël Écorchard 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. +*********************************************************************/ +/** + * Compute the histogram of intensities and publish it as an image. + */ + +// https://github.com/opencv/opencv/tree/3.4/samples/cpp/tutorial_code/Histograms_Matching/calcHist_Demo.cpp +/** + * @function calcHist_Demo.cpp + * @brief Demo code to use the function calcHist + * @author OpenCV team + */ + +// https://github.com/opencv/opencv/blob/3.4/samples/cpp/tutorial_code/Histograms_Matching/compareHist_Demo.cpp +/** + * @file compareHist_Demo.cpp + * @brief Sample code to use the function compareHist + * @author OpenCV team + */ + +#include +#include "opencv_apps/nodelet.h" +#include +#include +#include +#include +#include + +#include +#include + +#include + +#include "opencv_apps/CompareHistogramConfig.h" + +namespace opencv_apps +{ +class CompareHistogramNodelet : public opencv_apps::Nodelet +{ + std::string window_name_; + image_transport::Publisher img_pub_; + image_transport::Subscriber img_sub_; + image_transport::CameraSubscriber cam_sub_; + ros::Publisher msg_pub_, distance_pub_; + + boost::shared_ptr it_; + + typedef opencv_apps::CompareHistogramConfig Config; + typedef dynamic_reconfigure::Server ReconfigureServer; + + Config config_; + boost::shared_ptr reconfigure_server_; + + int queue_size_; + bool debug_view_; + int histogram_size_; + bool uniform_; + bool accumulate_; + std::vector reference_histogram_; + + void reconfigureCallback(Config& new_config, uint32_t level) + { + config_ = new_config; + histogram_size_ = config_.histogram_size; + uniform_ = config_.uniform; + accumulate_ = config_.accumulate; + } + + void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info) + { + doWork(msg, cam_info->header.frame_id); + } + + void imageCallback(const sensor_msgs::ImageConstPtr& msg) + { + doWork(msg, msg->header.frame_id); + } + + void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg) + { + try + { + // Convert the image into something opencv can handle. + cv::Mat frame; + if (msg->encoding == sensor_msgs::image_encodings::BGR8) + frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image; + else if (msg->encoding == sensor_msgs::image_encodings::MONO8) + frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::MONO8)->image; + + if (debug_view_) + { + cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE); + } + + // Draw contours + cv::Mat drawing; + bool publish_drawing = (img_pub_.getNumSubscribers() > 0); + + // Separate the image + std::vector planes; + cv::split(frame, planes); + + // Set the range + float range[] = { 0, 256 }; // the upper boundary is exclusive + const float* hist_range[] = { range }; + + // Compute the histograms + std::vector hist; + hist.resize(planes.size()); + for (unsigned int j = 0; j < hist.size(); j++) + { + cv::calcHist(&planes[j], 1, nullptr, cv::Mat(), hist[j], 1, &histogram_size_, hist_range, uniform_, accumulate_); + } + + // Publishe the results + std_msgs::Float64MultiArray hist_msg; + hist_msg.layout.dim.push_back(std_msgs::MultiArrayDimension()); + hist_msg.layout.dim.push_back(std_msgs::MultiArrayDimension()); + hist_msg.layout.dim[0].size = hist.size(); + hist_msg.layout.dim[0].stride = hist.size() * histogram_size_; + hist_msg.layout.dim[1].size = histogram_size_; + hist_msg.layout.dim[1].stride = histogram_size_; + for (auto& j : hist) + { + cv::normalize(j, j, 0, 1, cv::NORM_MINMAX, -1, cv::Mat()); + for (unsigned int i = 0; i < histogram_size_; i++) + { + hist_msg.data.push_back(j.at(i)); + } + } + msg_pub_.publish(hist_msg); + + // Apply the histogram comparison methods + if (!reference_histogram_.empty()) + { + int compare_method; + switch (config_.histogram_comparison_type) + { + case opencv_apps::CompareHistogram_Correlation: + compare_method = cv::HISTCMP_CORREL; + break; + case opencv_apps::CompareHistogram_Chi_Square: + compare_method = cv::HISTCMP_CHISQR; + break; + case opencv_apps::CompareHistogram_Intersection: + compare_method = cv::HISTCMP_INTERSECT; + break; + case opencv_apps::CompareHistogram_Bhattacharyya: + compare_method = cv::HISTCMP_BHATTACHARYYA; + break; + } + double distance = 1; + for (unsigned int j = 0; j < hist.size(); j++) + { + distance = distance * cv::compareHist(reference_histogram_[j], hist[j], compare_method); + } + std_msgs::Float64 distance_msg; + distance_msg.data = distance; + distance_pub_.publish(distance_msg); + } + + // Draw the histograms + if (debug_view_ || publish_drawing) + { + int hist_w = 512, hist_h = 400; + int bin_w = cvRound((double)hist_w / histogram_size_); + + drawing = cv::Mat(hist_h, hist_w, CV_8UC3, cv::Scalar(0, 0, 0)); + + // Normalize the result to ( 0, drawing.rows ) + for (auto& j : hist) + { + cv::normalize(j, j, 0, hist_h, cv::NORM_MINMAX, -1, cv::Mat()); + } + + // Draw for each channel + for (unsigned int j = 0; j < hist.size(); j++) + { + for (unsigned int i = 1; i < histogram_size_; i++) + { + cv::line(drawing, cv::Point(bin_w * (i - 1), hist_h - cvRound(hist[j].at(i - 1))), + cv::Point(bin_w * i, hist_h - cvRound(hist[j].at(i))), + cv::Scalar((j == 2 ? 255 : 0), (j == 1 ? 255 : 0), (j == 0 ? 255 : 0)), 2, 8, 0); + } + } + } + + //-- Show what you got + if (debug_view_) + { + cv::imshow(window_name_, drawing); + int c = cv::waitKey(1); + } + + // Publish the image. + if (publish_drawing) + { + sensor_msgs::Image::Ptr out_img = + cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::BGR8, drawing).toImageMsg(); + img_pub_.publish(out_img); + } + } + catch (cv::Exception& e) + { + NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line); + } + } + + void subscribe() // NOLINT(modernize-use-override) + { + NODELET_DEBUG("Subscribing to image topic."); + if (config_.use_camera_info) + cam_sub_ = it_->subscribeCamera("image", queue_size_, &CompareHistogramNodelet::imageCallbackWithInfo, this); + else + img_sub_ = it_->subscribe("image", queue_size_, &CompareHistogramNodelet::imageCallback, this); + } + + void unsubscribe() // NOLINT(modernize-use-override) + { + NODELET_DEBUG("Unsubscribing from image topic."); + img_sub_.shutdown(); + cam_sub_.shutdown(); + } + + void onInit() // NOLINT(modernize-use-override) + { + Nodelet::onInit(); + it_ = boost::shared_ptr(new image_transport::ImageTransport(*nh_)); + pnh_->param("queue_size", queue_size_, 3); + pnh_->param("debug_view", debug_view_, false); + if (pnh_->hasParam("reference_histogram")) + { + XmlRpc::XmlRpcValue param_val; + pnh_->getParam("reference_histogram", param_val); + if (param_val.getType() == XmlRpc::XmlRpcValue::TypeArray) + { + XmlRpc::XmlRpcValue param = param_val[0]; + reference_histogram_.resize(param_val.size()); + for (int j = 0; j < param_val.size(); j++) + { + reference_histogram_[j] = cv::Mat::zeros(param_val[0].size(), 1, CV_32F); + for (int i = 0; i < param_val[0].size(); i++) + { + reference_histogram_[j].at(0, i) = static_cast(param_val[j][i]); + } + ROS_INFO_STREAM("reference_histgram[" << j << "] : " << reference_histogram_[j]); + } + } + } + + window_name_ = "Histogram Window (" + ros::this_node::getName() + ")"; + + reconfigure_server_ = boost::make_shared >(*pnh_); + dynamic_reconfigure::Server::CallbackType f = boost::bind( + &CompareHistogramNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2); + reconfigure_server_->setCallback(f); + + img_pub_ = advertiseImage(*pnh_, "image", 1); + msg_pub_ = advertise(*pnh_, "histogram", 1); + distance_pub_ = advertise(*pnh_, "distance", 1); + + onInitPostProcess(); + } +}; +} // namespace opencv_apps + +#include +PLUGINLIB_EXPORT_CLASS(opencv_apps::CompareHistogramNodelet, nodelet::Nodelet); diff --git a/test/CMakeLists.txt b/test/CMakeLists.txt index 7e38dc04..3cd329b9 100644 --- a/test/CMakeLists.txt +++ b/test/CMakeLists.txt @@ -56,6 +56,9 @@ add_rostest(test-hls_color_filter.test ARGS gui:=false) add_rostest(test-hsv_color_filter.test ARGS gui:=false) add_rostest(test-lab_color_filter.test ARGS gui:=false) add_rostest(test-edge_detection.test ARGS gui:=false) +if(OpenCV_VERSION VERSION_GREATER "3.0") + add_rostest(test-compare_histogram.test ARGS gui:=false) +endif() add_rostest(test-equalize_histogram.test ARGS gui:=false) add_rostest(test-hough_lines.test ARGS gui:=false) @@ -105,6 +108,9 @@ if(roslaunch_VERSION VERSION_LESS "1.11.1") message(WARNING "roslaunch_add_file check fails with unsupported doc attributes ${roslaunch_VERSION}") else() file(GLOB LAUNCH_FILES *.test) + if(NOT OpenCV_VERSION VERSION_GREATER "3.0") + list(REMOVE_ITEM LAUNCH_FILES ${CMAKE_CURRENT_SOURCE_DIR}/test-compare_histogram.test) + endif() foreach(LAUNCH_FILE ${LAUNCH_FILES}) roslaunch_add_file_check(${LAUNCH_FILE}) endforeach() diff --git a/test/test-compare_histogram.test b/test/test-compare_histogram.test new file mode 100644 index 00000000..c147217f --- /dev/null +++ b/test/test-compare_histogram.test @@ -0,0 +1,66 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +