Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #include <string>
00031
00032 #include <opencv2/core/core.hpp>
00033 #include <opencv2/highgui/highgui.hpp>
00034 #include <opencv2/imgproc/imgproc.hpp>
00035
00036 #include <ros/ros.h>
00037 #include <nodelet/nodelet.h>
00038 #include <image_transport/image_transport.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 #include <sensor_msgs/Image.h>
00041 #include <cv_bridge/cv_bridge.h>
00042 #include <swri_image_util/image_normalization.h>
00043
00044 #include <swri_math_util/math_util.h>
00045
00046 namespace swri_image_util
00047 {
00048 class ContrastStretchNodelet : public nodelet::Nodelet
00049 {
00050 public:
00051 ContrastStretchNodelet() :
00052 bins_(8),
00053 max_min_(0.0),
00054 min_max_(0.0),
00055 over_exposure_threshold_(255.0),
00056 over_exposure_dilation_(3)
00057 {
00058 }
00059
00060 ~ContrastStretchNodelet()
00061 {
00062 }
00063
00064 void onInit()
00065 {
00066 ros::NodeHandle &node = getNodeHandle();
00067 ros::NodeHandle &priv = getPrivateNodeHandle();
00068
00069 priv.param("bins", bins_, bins_);
00070 priv.param("max_min", max_min_, max_min_);
00071 priv.param("min_max", min_max_, min_max_);
00072 priv.param("over_exposure_threshold", over_exposure_threshold_, over_exposure_threshold_);
00073 priv.param("over_exposure_dilation", over_exposure_dilation_, over_exposure_dilation_);
00074
00075 std::string mask;
00076 priv.param("mask", mask, std::string(""));
00077 if (!mask.empty())
00078 {
00079 mask_ = cv::imread(mask, 0);
00080 }
00081
00082 image_transport::ImageTransport it(node);
00083 image_pub_ = it.advertise("normalized_image", 1);
00084 image_sub_ = it.subscribe("image", 1, &ContrastStretchNodelet::ImageCallback, this);
00085 }
00086
00087 void ImageCallback(const sensor_msgs::ImageConstPtr& image)
00088 {
00089 cv_bridge::CvImagePtr cv_image = cv_bridge::toCvCopy(image);
00090
00091 if (mask_.empty())
00092 {
00093 mask_ = cv::Mat::ones(cv_image->image.size(), CV_8U);
00094 }
00095 else if (mask_.rows != cv_image->image.rows || mask_.cols != cv_image->image.cols)
00096 {
00097 cv::resize(mask_, mask_, cv_image->image.size(), 1.0, 1.0, cv::INTER_NEAREST);
00098 }
00099
00100 cv::Mat mask;
00101
00102 if (over_exposure_threshold_ < 255 && over_exposure_threshold_ > 0)
00103 {
00104 cv::Mat over_exposed = cv_image->image > over_exposure_threshold_;
00105 cv::Mat element = cv::getStructuringElement(
00106 cv::MORPH_ELLIPSE,
00107 cv::Size(2 * over_exposure_dilation_ + 1, 2 * over_exposure_dilation_ + 1 ),
00108 cv::Point(over_exposure_dilation_, over_exposure_dilation_ ));
00109 cv::dilate(over_exposed, over_exposed, element);
00110
00111 mask = mask_.clone();
00112 mask.setTo(0, over_exposed);
00113 }
00114 else
00115 {
00116 mask = mask_;
00117 }
00118
00119 swri_image_util::ContrastStretch(bins_, cv_image->image, cv_image->image, mask, max_min_, min_max_);
00120
00121 image_pub_.publish(cv_image->toImageMsg());
00122 }
00123
00124 private:
00125 int32_t bins_;
00126 double max_min_;
00127 double min_max_;
00128 double over_exposure_threshold_;
00129 int32_t over_exposure_dilation_;
00130
00131 cv::Mat mask_;
00132
00133 image_transport::Subscriber image_sub_;
00134 image_transport::Publisher image_pub_;
00135
00136 };
00137 }
00138
00139
00140 #include <pluginlib/class_list_macros.h>
00141 PLUGINLIB_DECLARE_CLASS(
00142 swri_image_util,
00143 contrast_stretch,
00144 swri_image_util::ContrastStretchNodelet,
00145 nodelet::Nodelet)