55 #if CV_MAJOR_VERSION >= 3 56 #include "opencv2/core/ocl.hpp" 57 #else // OpenCV Version 2 does not have UMat, use Mat instead 63 #include <opencv2/highgui/highgui.hpp> 64 #include <opencv2/imgproc/imgproc.hpp> 66 #include <dynamic_reconfigure/server.h> 68 #include "opencv_apps/EqualizeHistogramConfig.h" 83 typedef opencv_apps::EqualizeHistogramConfig
Config;
91 #if CV_MAJOR_VERSION >= 3 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;
107 doWork(msg, cam_info->header.frame_id);
112 doWork(msg, msg->header.frame_id);
115 void doWork(
const sensor_msgs::ImageConstPtr& msg,
const std::string& input_frame_from_msg)
121 #if CV_MAJOR_VERSION >= 3 135 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
140 if (frame.channels() > 1)
142 cv::cvtColor(frame, gray, cv::COLOR_BGR2GRAY);
149 switch (config_.histogram_equalization_type)
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);
158 case opencv_apps::EqualizeHistogram_EqualizeHist:
159 equalizeHist(gray, dst);
166 cv::imshow(window_name_, dst);
167 int c = cv::waitKey(1);
171 #if CV_MAJOR_VERSION >= 3 172 sensor_msgs::Image::Ptr out_img =
175 sensor_msgs::Image::Ptr out_img =
178 out_img->header.frame_id = input_frame_from_msg;
181 catch (cv::Exception& e)
183 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
190 if (config_.use_camera_info)
191 cam_sub_ = it_->subscribeCamera(
"image", queue_size_, &EqualizeHistogramNodelet::imageCallbackWithInfo,
this);
193 img_sub_ = it_->subscribe(
"image", queue_size_, &EqualizeHistogramNodelet::imageCallback,
this);
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);
215 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
216 dynamic_reconfigure::Server<Config>::CallbackType
f = boost::bind(
218 reconfigure_server_->setCallback(f);
220 img_pub_ = advertiseImage(*pnh_,
"image", 1);
222 #if CV_MAJOR_VERSION >= 3 223 cv::ocl::setUseOpenCL(use_opencl_);
231 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
cv::Size clahe_tile_size_
#define NODELET_ERROR(...)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Demo code to calculate moments.
image_transport::Publisher img_pub_
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)
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
void publish(const sensor_msgs::Image &message) const
cv::Ptr< cv::CLAHE > clahe_
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_
image_transport::Subscriber img_sub_
opencv_apps::EqualizeHistogramConfig Config