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
00035 #include <ros/ros.h>
00036 #include <nodelet/nodelet.h>
00037 #include <image_transport/image_transport.h>
00038 #include <sensor_msgs/image_encodings.h>
00039 #include <sensor_msgs/Image.h>
00040 #include <cv_bridge/cv_bridge.h>
00041 #include <swri_image_util/image_normalization.h>
00042
00043 #include <swri_math_util/math_util.h>
00044
00045 namespace swri_image_util
00046 {
00047 class NormalizeResponseNodelet : public nodelet::Nodelet
00048 {
00049 public:
00050 NormalizeResponseNodelet() :
00051 filter_size_(9),
00052 filter_cap_(31)
00053 {
00054 }
00055
00056 ~NormalizeResponseNodelet()
00057 {
00058 }
00059
00060 void onInit()
00061 {
00062 ros::NodeHandle &node = getNodeHandle();
00063 ros::NodeHandle &priv = getPrivateNodeHandle();
00064
00065 priv.param("filter_size", filter_size_, filter_size_);
00066 priv.param("filter_cap", filter_cap_, filter_cap_);
00067
00068 buffer_.create(1, 10000000, CV_8U);
00069
00070 image_transport::ImageTransport it(node);
00071 image_pub_ = it.advertise("normalized_image", 1);
00072 image_sub_ = it.subscribe("image", 1, &NormalizeResponseNodelet::ImageCallback, this);
00073 }
00074
00075 void ImageCallback(const sensor_msgs::ImageConstPtr& image)
00076 {
00077 cv_bridge::CvImageConstPtr cv_image = cv_bridge::toCvShare(image);
00078
00079 if (image->encoding == sensor_msgs::image_encodings::MONO8)
00080 {
00081 swri_image_util::NormalizeResponse(cv_image->image, normalized_, filter_size_, filter_cap_, buffer_.ptr());
00082 cv_bridge::CvImage normalized_image;
00083 normalized_image.header = image->header;
00084 normalized_image.encoding = image->encoding;
00085 normalized_image.image = normalized_;
00086 image_pub_.publish(normalized_image.toImageMsg());
00087 }
00088 else
00089 {
00090 ROS_WARN("Unsupported image encoding: %s", image->encoding.c_str());
00091 }
00092 }
00093
00094 private:
00095 int32_t filter_size_;
00096 int32_t filter_cap_;
00097
00098 cv::Mat normalized_;
00099 cv::Mat buffer_;
00100
00101 image_transport::Subscriber image_sub_;
00102 image_transport::Publisher image_pub_;
00103 };
00104 }
00105
00106
00107 #include <pluginlib/class_list_macros.h>
00108 PLUGINLIB_DECLARE_CLASS(
00109 swri_image_util,
00110 normalize_response,
00111 swri_image_util::NormalizeResponseNodelet,
00112 nodelet::Nodelet)