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
00031
00032
00033
00034
00035
00036
00043 #include <ros/ros.h>
00044 #include "opencv_apps/nodelet.h"
00045 #include <image_transport/image_transport.h>
00046 #include <sensor_msgs/image_encodings.h>
00047 #include <cv_bridge/cv_bridge.h>
00048
00049 #include <iostream>
00050 #include <vector>
00051
00052 #include "opencv2/imgproc/imgproc.hpp"
00053 #include "opencv2/highgui/highgui.hpp"
00054 #include "opencv2/features2d/features2d.hpp"
00055
00056 #include <dynamic_reconfigure/server.h>
00057 #include "opencv_apps/SmoothingConfig.h"
00058
00060 int MAX_KERNEL_LENGTH = 31;
00061
00062 namespace smoothing {
00063 class SmoothingNodelet : public opencv_apps::Nodelet
00064 {
00065 image_transport::Publisher img_pub_;
00066 image_transport::Subscriber img_sub_;
00067 image_transport::CameraSubscriber cam_sub_;
00068 ros::Publisher msg_pub_;
00069
00070 boost::shared_ptr<image_transport::ImageTransport> it_;
00071
00072 typedef smoothing::SmoothingConfig Config;
00073 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00074 Config config_;
00075 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00076
00077 bool debug_view_;
00078 ros::Time prev_stamp_;
00079
00080 std::string window_name_;
00081 static bool need_config_update_;
00082
00083 int kernel_size_;
00084
00085 void reconfigureCallback(Config &new_config, uint32_t level)
00086 {
00087 config_ = new_config;
00088 kernel_size_ = (config_.kernel_size/2)*2+1;
00089 }
00090
00091 const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00092 {
00093 if (frame.empty())
00094 return image_frame;
00095 return frame;
00096 }
00097
00098 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00099 {
00100 do_work(msg, cam_info->header.frame_id);
00101 }
00102
00103 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00104 {
00105 do_work(msg, msg->header.frame_id);
00106 }
00107
00108 static void trackbarCallback( int, void* )
00109 {
00110 need_config_update_ = true;
00111 }
00112
00113 void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00114 {
00115
00116 try
00117 {
00118
00119 cv::Mat in_image = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00120
00121
00122 if( debug_view_) {
00124 char kernel_label[] = "Kernel Size : ";
00125
00126 cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00127 cv::createTrackbar( kernel_label, window_name_, &kernel_size_, MAX_KERNEL_LENGTH, trackbarCallback);
00128 if (need_config_update_) {
00129 kernel_size_ = (kernel_size_/2)*2+1;
00130 config_.kernel_size = kernel_size_;
00131 reconfigure_server_->updateConfig(config_);
00132 need_config_update_ = false;
00133 }
00134 }
00135
00136 cv::Mat out_image = in_image.clone();
00137 int i = kernel_size_;
00138 switch (config_.filter_type) {
00139 case smoothing::Smoothing_Homogeneous_Blur:
00140 {
00142 ROS_DEBUG_STREAM("Applying Homogeneous blur with kernel size " << i );
00143 cv::blur( in_image, out_image, cv::Size( i, i ), cv::Point(-1,-1) );
00144 break;
00145 }
00146 case smoothing::Smoothing_Gaussian_Blur:
00147 {
00149 ROS_DEBUG_STREAM("Applying Gaussian blur with kernel size " << i );
00150 cv::GaussianBlur( in_image, out_image, cv::Size( i, i ), 0, 0 );
00151 break;
00152 }
00153 case smoothing::Smoothing_Median_Blur:
00154 {
00156 ROS_DEBUG_STREAM("Applying Median blur with kernel size " << i );
00157 cv::medianBlur ( in_image, out_image, i );
00158 break;
00159 }
00160 case smoothing::Smoothing_Bilateral_Filter:
00161 {
00163 ROS_DEBUG_STREAM("Applying Bilateral blur with kernel size " << i );
00164 cv::bilateralFilter ( in_image, out_image, i, i*2, i/2 );
00165 break;
00166 }
00167 }
00168
00169
00170 if( debug_view_) {
00171 cv::imshow( window_name_, out_image );
00172 int c = cv::waitKey(1);
00173 }
00174
00175
00176 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", out_image).toImageMsg();
00177 img_pub_.publish(out_img);
00178 }
00179 catch (cv::Exception &e)
00180 {
00181 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00182 }
00183
00184 prev_stamp_ = msg->header.stamp;
00185 }
00186
00187 void subscribe()
00188 {
00189 NODELET_DEBUG("Subscribing to image topic.");
00190 if (config_.use_camera_info)
00191 cam_sub_ = it_->subscribeCamera("image", 3, &SmoothingNodelet::imageCallbackWithInfo, this);
00192 else
00193 img_sub_ = it_->subscribe("image", 3, &SmoothingNodelet::imageCallback, this);
00194 }
00195
00196 void unsubscribe()
00197 {
00198 NODELET_DEBUG("Unsubscribing from image topic.");
00199 img_sub_.shutdown();
00200 cam_sub_.shutdown();
00201 }
00202
00203 public:
00204 virtual void onInit()
00205 {
00206 Nodelet::onInit();
00207 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00208
00209 pnh_->param("debug_view", debug_view_, false);
00210 if (debug_view_) {
00211 always_subscribe_ = true;
00212 }
00213 prev_stamp_ = ros::Time(0, 0);
00214
00215 window_name_ = "Smoothing Demo";
00216 kernel_size_ = 7;
00217
00218 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00219 dynamic_reconfigure::Server<Config>::CallbackType f =
00220 boost::bind(&SmoothingNodelet::reconfigureCallback, this, _1, _2);
00221 reconfigure_server_->setCallback(f);
00222
00223 img_pub_ = advertiseImage(*pnh_, "image", 1);
00224
00225 onInitPostProcess();
00226 }
00227 };
00228 bool SmoothingNodelet::need_config_update_ = false;
00229 }
00230
00231 #include <pluginlib/class_list_macros.h>
00232 PLUGINLIB_EXPORT_CLASS(smoothing::SmoothingNodelet, nodelet::Nodelet);