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