|
| 1 | +/********************************************************************* |
| 2 | +* Software License Agreement (BSD License) |
| 3 | +* |
| 4 | +* Copyright (c) 2020, Gaël Écorchard, Czech Technical University. |
| 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 Gaël Écorchard 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 | +*********************************************************************/ |
| 34 | +/** |
| 35 | + * Compute the histogram of intensities and publish it as an image. |
| 36 | + */ |
| 37 | + |
| 38 | +#include <vector> |
| 39 | + |
| 40 | +#include <cv_bridge/cv_bridge.h> |
| 41 | +//#include <dynamic_reconfigure/server.h> |
| 42 | +#include <image_transport/image_transport.h> |
| 43 | +#include <opencv_apps/nodelet.h> |
| 44 | +#include <opencv2/highgui/highgui.hpp> |
| 45 | +#include <opencv2/imgproc/imgproc.hpp> |
| 46 | +#include <ros/ros.h> |
| 47 | +#include <sensor_msgs/Image.h> |
| 48 | +#include <sensor_msgs/image_encodings.h> |
| 49 | + |
| 50 | +namespace opencv_apps |
| 51 | +{ |
| 52 | + |
| 53 | +namespace intensity_histogram |
| 54 | +{ |
| 55 | + |
| 56 | +static const std::string OPENCV_WINDOW = "Image histogram"; |
| 57 | + |
| 58 | +cv::Mat grayHistogram(cv_bridge::CvImageConstPtr img) |
| 59 | +{ |
| 60 | + /* Inspired by https://github.com/opencv/opencv/tree/3.4/samples/cpp/tutorial_code/Histograms_Matching/calcHist_Demo.cpp. */ |
| 61 | + constexpr bool uniform = true; |
| 62 | + constexpr bool accumulate = false; |
| 63 | + constexpr int bin_count = 256; |
| 64 | + |
| 65 | + float range[] = {0, 256}; //the upper boundary is exclusive |
| 66 | + const float* hist_range = {range}; |
| 67 | + cv::Mat intensity_hist; |
| 68 | + cv::calcHist(&img->image, 1, 0, cv::Mat(), intensity_hist, 1, &bin_count, &hist_range, uniform, accumulate); |
| 69 | + int hist_w = 512; |
| 70 | + int hist_h = 400; |
| 71 | + int bin_w = cvRound(static_cast<double>(hist_w / bin_count)); |
| 72 | + cv::Mat hist_image(hist_h, hist_w, CV_8UC1, cv::Scalar(0)); |
| 73 | + cv::normalize(intensity_hist, intensity_hist, 0, hist_image.rows, cv::NORM_MINMAX, -1, cv::Mat()); |
| 74 | + for (unsigned int i = 1; i < bin_count; i++) |
| 75 | + { |
| 76 | + cv::line(hist_image, |
| 77 | + cv::Point(bin_w * (i-1), hist_h - cvRound(intensity_hist.at<float>(i-1))), |
| 78 | + cv::Point(bin_w * (i), hist_h - cvRound(intensity_hist.at<float>(i))), |
| 79 | + cv::Scalar(255), 2, 8, 0); |
| 80 | + } |
| 81 | + return hist_image; |
| 82 | +} |
| 83 | + |
| 84 | +cv::Mat bgrHistogram(cv_bridge::CvImageConstPtr img) |
| 85 | +{ |
| 86 | + /* Inspired by https://github.com/opencv/opencv/tree/3.4/samples/cpp/tutorial_code/Histograms_Matching/calcHist_Demo.cpp. */ |
| 87 | + constexpr bool uniform = true; |
| 88 | + constexpr bool accumulate = false; |
| 89 | + constexpr int bin_count = 256; |
| 90 | + |
| 91 | + std::vector<cv::Mat> bgr_planes; |
| 92 | + cv::split(img->image, bgr_planes); |
| 93 | + |
| 94 | + float range[] = {0, 256}; //the upper boundary is exclusive |
| 95 | + const float* hist_range = {range}; |
| 96 | + cv::Mat b_hist; |
| 97 | + cv::Mat g_hist; |
| 98 | + cv::Mat r_hist; |
| 99 | + cv::calcHist(&bgr_planes[0], 1, 0, cv::Mat(), b_hist, 1, &bin_count, &hist_range, uniform, accumulate); |
| 100 | + cv::calcHist(&bgr_planes[1], 1, 0, cv::Mat(), g_hist, 1, &bin_count, &hist_range, uniform, accumulate); |
| 101 | + cv::calcHist(&bgr_planes[2], 1, 0, cv::Mat(), r_hist, 1, &bin_count, &hist_range, uniform, accumulate); |
| 102 | + int hist_w = 512; |
| 103 | + int hist_h = 400; |
| 104 | + int bin_w = cvRound(static_cast<double>(hist_w / bin_count)); |
| 105 | + cv::Mat hist_image(hist_h, hist_w, CV_8UC3, cv::Scalar(0, 0, 0)); |
| 106 | + cv::normalize(b_hist, b_hist, 0, hist_image.rows, cv::NORM_MINMAX, -1, cv::Mat()); |
| 107 | + cv::normalize(g_hist, g_hist, 0, hist_image.rows, cv::NORM_MINMAX, -1, cv::Mat()); |
| 108 | + cv::normalize(r_hist, r_hist, 0, hist_image.rows, cv::NORM_MINMAX, -1, cv::Mat()); |
| 109 | + for (unsigned int i = 1; i < bin_count; i++) |
| 110 | + { |
| 111 | + cv::line(hist_image, |
| 112 | + cv::Point(bin_w * (i-1), hist_h - cvRound(b_hist.at<float>(i-1))), |
| 113 | + cv::Point(bin_w * (i), hist_h - cvRound(b_hist.at<float>(i))), |
| 114 | + cv::Scalar(255, 0, 0), 2, 8, 0); |
| 115 | + cv::line(hist_image, |
| 116 | + cv::Point(bin_w * (i-1), hist_h - cvRound(g_hist.at<float>(i-1))), |
| 117 | + cv::Point(bin_w * (i), hist_h - cvRound(g_hist.at<float>(i))), |
| 118 | + cv::Scalar(0, 255, 0), 2, 8, 0); |
| 119 | + cv::line(hist_image, |
| 120 | + cv::Point(bin_w * (i-1), hist_h - cvRound(r_hist.at<float>(i-1))), |
| 121 | + cv::Point(bin_w * (i), hist_h - cvRound(r_hist.at<float>(i))), |
| 122 | + cv::Scalar(0, 0, 255), 2, 8, 0); |
| 123 | + } |
| 124 | + return hist_image; |
| 125 | +} |
| 126 | + |
| 127 | +class IntensityHistogram |
| 128 | +{ |
| 129 | + |
| 130 | + public: |
| 131 | + |
| 132 | + IntensityHistogram() : |
| 133 | + it_(nh_) |
| 134 | + { |
| 135 | + image_sub_ = it_.subscribe("image", queue_size_, &IntensityHistogram::imageCallback, this); |
| 136 | + hist_pub_ = it_.advertise("image_hist", 1); |
| 137 | + |
| 138 | + ros::NodeHandle private_nh("~"); |
| 139 | + private_nh.param("queue_size", queue_size_, 1); |
| 140 | + private_nh.param("debug_view", debug_view_, false); |
| 141 | + if (debug_view_) |
| 142 | + { |
| 143 | + cv::namedWindow(OPENCV_WINDOW); |
| 144 | + } |
| 145 | + } |
| 146 | + |
| 147 | + ~IntensityHistogram() |
| 148 | + { |
| 149 | + if (debug_view_) |
| 150 | + { |
| 151 | + cv::destroyWindow(OPENCV_WINDOW); |
| 152 | + } |
| 153 | + } |
| 154 | + |
| 155 | + void imageCallback(const sensor_msgs::ImageConstPtr& msg) |
| 156 | + { |
| 157 | + cv_bridge::CvImageConstPtr cv_ptr; |
| 158 | + try |
| 159 | + { |
| 160 | + cv_ptr = cv_bridge::toCvShare(msg); |
| 161 | + } |
| 162 | + catch (cv_bridge::Exception& e) |
| 163 | + { |
| 164 | + ROS_ERROR("cv_bridge exception: %s", e.what()); |
| 165 | + return; |
| 166 | + } |
| 167 | + |
| 168 | + cv::Mat out_img; |
| 169 | + sensor_msgs::Image::Ptr out_img_msg; |
| 170 | + if (cv_ptr->image.channels() == 1) |
| 171 | + { |
| 172 | + out_img = grayHistogram(cv_ptr); |
| 173 | + out_img_msg = cv_bridge::CvImage( |
| 174 | + msg->header, sensor_msgs::image_encodings::MONO8, out_img).toImageMsg(); |
| 175 | + |
| 176 | + } |
| 177 | + else |
| 178 | + { |
| 179 | + out_img = bgrHistogram(cv_ptr); |
| 180 | + out_img_msg = cv_bridge::CvImage( |
| 181 | + msg->header, sensor_msgs::image_encodings::RGB8, out_img).toImageMsg(); |
| 182 | + } |
| 183 | + |
| 184 | + if (debug_view_) |
| 185 | + { |
| 186 | + // Update GUI Window |
| 187 | + cv::imshow(OPENCV_WINDOW, out_img); |
| 188 | + cv::waitKey(3); |
| 189 | + } |
| 190 | + |
| 191 | + hist_pub_.publish(out_img_msg); |
| 192 | + } |
| 193 | + |
| 194 | + private: |
| 195 | + |
| 196 | + ros::NodeHandle nh_; |
| 197 | + image_transport::ImageTransport it_; |
| 198 | + image_transport::Subscriber image_sub_; |
| 199 | + image_transport::Publisher hist_pub_; |
| 200 | + int queue_size_; |
| 201 | + bool debug_view_; |
| 202 | +}; |
| 203 | + |
| 204 | +} /* namespace intensity_histogram. */ |
| 205 | + |
| 206 | +class IntensityHistogramNodelet : public nodelet::Nodelet |
| 207 | +{ |
| 208 | + |
| 209 | + public: |
| 210 | + |
| 211 | + virtual void onInit() // NOLINT(modernize-use-override) |
| 212 | + { |
| 213 | + intensity_histogram::IntensityHistogram ih; |
| 214 | + ros::spin(); |
| 215 | + } |
| 216 | +}; |
| 217 | + |
| 218 | +} /* namespace opencv_apps. */ |
| 219 | + |
| 220 | +#include <pluginlib/class_list_macros.h> |
| 221 | +PLUGINLIB_EXPORT_CLASS(opencv_apps::IntensityHistogramNodelet, nodelet::Nodelet); |
0 commit comments