Go to the documentation of this file.
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
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
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:
153 clahe_ = cv::createCLAHE();
158 case opencv_apps::EqualizeHistogram_EqualizeHist:
159 equalizeHist(gray, 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);
209 #if CV_MAJOR_VERSION >= 3
210 pnh_->param(
"use_opencl", use_opencl_,
true);
216 dynamic_reconfigure::Server<Config>::CallbackType
f = boost::bind(
222 #if CV_MAJOR_VERSION >= 3
223 cv::ocl::setUseOpenCL(use_opencl_);
231 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H
#define NODELET_ERROR(...)
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
void doWork(const sensor_msgs::ImageConstPtr &msg, const std::string &input_frame_from_msg)
sensor_msgs::ImagePtr toImageMsg() const
cv::Ptr< cv::CLAHE > clahe_
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics.
void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
void reconfigureCallback(Config &new_config, uint32_t level)
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
image_transport::Publisher advertiseImage(ros::NodeHandle &nh, const std::string &topic, int queue_size)
Advertise an image topic and watch the publisher. Publishers which are created by this method....
boost::shared_ptr< image_transport::ImageTransport > it_
image_transport::Subscriber img_sub_
opencv_apps::EqualizeHistogramConfig Config
cv::Size clahe_tile_size_
boost::shared_ptr< ReconfigureServer > reconfigure_server_
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
void publish(const sensor_msgs::Image &message) const
Demo code to calculate moments.
image_transport::Publisher img_pub_
const ROSCPP_DECL std::string & getName()
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
Demo code for equalizeHist function.
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
dynamic_reconfigure::Server< Config > ReconfigureServer
PLUGINLIB_EXPORT_CLASS(opencv_apps::EqualizeHistogramNodelet, nodelet::Nodelet)
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method.
image_transport::CameraSubscriber cam_sub_
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method.
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
#define NODELET_DEBUG(...)
opencv_apps
Author(s): Kei Okada
autogenerated on Fri May 23 2025 02:49:49