equalize_histogram_nodelet.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2020, Ivan Tarifa.
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 Ivan Tarifa 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 // https://github.com/opencv/opencv/blob/2.4/samples/cpp/tutorial_code/Histograms_Matching/EqualizeHist_Demo.cpp
42 // https://github.com/opencv/opencv/blob/3.4/samples/tapi/clahe.cpp
49 #include <ros/ros.h>
50 #include "opencv_apps/nodelet.h"
53 #include <cv_bridge/cv_bridge.h>
54 
55 #if CV_MAJOR_VERSION >= 3
56 #include "opencv2/core/ocl.hpp"
57 #else // OpenCV Version 2 does not have UMat, use Mat instead
58 namespace cv
59 {
60 typedef Mat UMat;
61 }
62 #endif
63 #include <opencv2/highgui/highgui.hpp>
64 #include <opencv2/imgproc/imgproc.hpp>
65 
66 #include <dynamic_reconfigure/server.h>
67 
68 #include "opencv_apps/EqualizeHistogramConfig.h"
69 
70 namespace opencv_apps
71 {
73 {
74  std::string window_name_;
78 
79  cv::Ptr<cv::CLAHE> clahe_;
80 
82 
83  typedef opencv_apps::EqualizeHistogramConfig Config;
84  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
85 
86  Config config_;
88 
91 #if CV_MAJOR_VERSION >= 3
92  bool use_opencl_;
93 #endif
94 
95  cv::Size clahe_tile_size_;
97 
98  void reconfigureCallback(Config& new_config, uint32_t level)
99  {
100  config_ = new_config;
101  clahe_tile_size_ = cv::Size(config_.clahe_tile_size_x, config_.clahe_tile_size_y);
102  clahe_clip_limit_ = config_.clahe_clip_limit;
103  }
104 
105  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
106  {
107  doWork(msg, cam_info->header.frame_id);
108  }
109 
110  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
111  {
112  doWork(msg, msg->header.frame_id);
113  }
114 
115  void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
116  {
117  try
118  {
119  // Convert the image into something opencv can handle.
120  cv::UMat frame;
121 #if CV_MAJOR_VERSION >= 3
122  if (msg->encoding == sensor_msgs::image_encodings::BGR8)
123  frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image.getUMat(cv::ACCESS_RW);
124  else if (msg->encoding == sensor_msgs::image_encodings::MONO8)
125  frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::MONO8)->image.getUMat(cv::ACCESS_RW);
126 #else
127  if (msg->encoding == sensor_msgs::image_encodings::BGR8)
129  else if (msg->encoding == sensor_msgs::image_encodings::MONO8)
131 #endif
132 
133  if (debug_view_)
134  {
135  cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
136  }
137 
138  // Do the work
139  cv::UMat gray, dst;
140  if (frame.channels() > 1)
141  {
142  cv::cvtColor(frame, gray, cv::COLOR_BGR2GRAY);
143  }
144  else
145  {
146  frame.copyTo(gray);
147  }
148 
149  switch (config_.histogram_equalization_type)
150  {
151  case opencv_apps::EqualizeHistogram_Clahe:
152  if (clahe_ == nullptr)
153  clahe_ = cv::createCLAHE();
154  clahe_->setTilesGridSize(clahe_tile_size_);
155  clahe_->setClipLimit(clahe_clip_limit_);
156  clahe_->apply(gray, dst);
157  break;
158  case opencv_apps::EqualizeHistogram_EqualizeHist:
159  equalizeHist(gray, dst);
160  break;
161  }
162 
163  //-- Show what you got
164  if (debug_view_)
165  {
166  cv::imshow(window_name_, dst);
167  int c = cv::waitKey(1);
168  }
169 
170  // Publish the image.
171 #if CV_MAJOR_VERSION >= 3
172  sensor_msgs::Image::Ptr out_img =
173  cv_bridge::CvImage(msg->header, sensor_msgs::image_encodings::MONO8, dst.getMat(cv::ACCESS_READ)).toImageMsg();
174 #else
175  sensor_msgs::Image::Ptr out_img =
177 #endif
178  out_img->header.frame_id = input_frame_from_msg;
179  img_pub_.publish(out_img);
180  }
181  catch (cv::Exception& e)
182  {
183  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
184  }
185  }
186 
187  void subscribe() // NOLINT(modernize-use-override)
188  {
189  NODELET_DEBUG("Subscribing to image topic.");
190  if (config_.use_camera_info)
191  cam_sub_ = it_->subscribeCamera("image", queue_size_, &EqualizeHistogramNodelet::imageCallbackWithInfo, this);
192  else
193  img_sub_ = it_->subscribe("image", queue_size_, &EqualizeHistogramNodelet::imageCallback, this);
194  }
195 
196  void unsubscribe() // NOLINT(modernize-use-override)
197  {
198  NODELET_DEBUG("Unsubscribing from image topic.");
199  img_sub_.shutdown();
200  cam_sub_.shutdown();
201  }
202 
203  void onInit() // NOLINT(modernize-use-override)
204  {
205  Nodelet::onInit();
207  pnh_->param("queue_size", queue_size_, 3);
208  pnh_->param("debug_view", debug_view_, false);
209 #if CV_MAJOR_VERSION >= 3
210  pnh_->param("use_opencl", use_opencl_, true);
211 #endif
212 
213  window_name_ = "Equalize Histogram Window (" + ros::this_node::getName() + ")";
214 
215  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
216  dynamic_reconfigure::Server<Config>::CallbackType f = boost::bind(
217  &EqualizeHistogramNodelet::reconfigureCallback, this, boost::placeholders::_1, boost::placeholders::_2);
218  reconfigure_server_->setCallback(f);
219 
220  img_pub_ = advertiseImage(*pnh_, "image", 1);
221 
222 #if CV_MAJOR_VERSION >= 3
223  cv::ocl::setUseOpenCL(use_opencl_);
224 #endif
225 
226  onInitPostProcess();
227  }
228 };
229 } // namespace opencv_apps
230 
231 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
233 #else
235 #endif
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_ERROR(...)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
f
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet.h:90
Demo code to calculate moments.
Definition: nodelet.h:68
boost::arg< 2 > _2
Definition: nodelet.cpp:45
ROSCPP_DECL const std::string & getName()
Demo code for equalizeHist function.
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
dynamic_reconfigure::Server< Config > ReconfigureServer
image_transport::CameraSubscriber cam_sub_
sensor_msgs::ImagePtr toImageMsg() const
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
PLUGINLIB_EXPORT_CLASS(opencv_apps::EqualizeHistogramNodelet, nodelet::Nodelet)
boost::arg< 1 > _1
Definition: nodelet.cpp:44
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
void publish(const sensor_msgs::Image &message) const
void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
void reconfigureCallback(Config &new_config, uint32_t level)
#define NODELET_DEBUG(...)
boost::shared_ptr< ReconfigureServer > reconfigure_server_
boost::shared_ptr< image_transport::ImageTransport > it_
opencv_apps::EqualizeHistogramConfig Config


opencv_apps
Author(s): Kei Okada
autogenerated on Thu Feb 2 2023 03:40:24