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
00041 #include <image_transport/image_transport.h>
00042 #include <sensor_msgs/image_encodings.h>
00043 #include <cv_bridge/cv_bridge.h>
00044 #include "opencv2/core/core.hpp"
00045 #include "opencv2/imgproc/imgproc.hpp"
00046 #include "opencv2/highgui/highgui.hpp"
00047
00048 #include "opencv_apps/nodelet.h"
00049 #include "opencv_apps/DiscreteFourierTransformConfig.h"
00050
00051 #include <dynamic_reconfigure/server.h>
00052
00053 namespace opencv_apps
00054 {
00055 class DiscreteFourierTransformNodelet : public opencv_apps::Nodelet
00056 {
00057 image_transport::Publisher img_pub_;
00058 image_transport::Subscriber img_sub_;
00059 image_transport::CameraSubscriber cam_sub_;
00060
00061 boost::shared_ptr<image_transport::ImageTransport> it_;
00062
00063 typedef opencv_apps::DiscreteFourierTransformConfig Config;
00064 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00065 Config config_;
00066 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00067
00068 int queue_size_;
00069 bool debug_view_;
00070 ros::Time prev_stamp_;
00071
00072 boost::mutex mutex_;
00073
00074 std::string window_name_;
00075
00076 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00077 {
00078 doWork(msg, cam_info->header.frame_id);
00079 }
00080
00081 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00082 {
00083 doWork(msg, msg->header.frame_id);
00084 }
00085
00086 void subscribe()
00087 {
00088 NODELET_DEBUG("Subscribing to image topic.");
00089 if (config_.use_camera_info)
00090 cam_sub_ =
00091 it_->subscribeCamera("image", queue_size_, &DiscreteFourierTransformNodelet::imageCallbackWithInfo, this);
00092 else
00093 img_sub_ = it_->subscribe("image", queue_size_, &DiscreteFourierTransformNodelet::imageCallback, this);
00094 }
00095
00096 void unsubscribe()
00097 {
00098 NODELET_DEBUG("Unsubscribing from image topic.");
00099 img_sub_.shutdown();
00100 cam_sub_.shutdown();
00101 }
00102
00103 void reconfigureCallback(Config& config, uint32_t level)
00104 {
00105 boost::mutex::scoped_lock lock(mutex_);
00106 config_ = config;
00107 }
00108
00109 void doWork(const sensor_msgs::Image::ConstPtr& image_msg, const std::string& input_frame_from_msg)
00110 {
00111
00112 try
00113 {
00114 cv::Mat src_image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
00115 if (src_image.channels() > 1)
00116 {
00117 cv::cvtColor(src_image, src_image, CV_BGR2GRAY);
00118 }
00119
00120 cv::Mat padded;
00121 int m = cv::getOptimalDFTSize(src_image.rows);
00122 int n = cv::getOptimalDFTSize(src_image.cols);
00123 cv::copyMakeBorder(src_image, padded, 0, m - src_image.rows, 0, n - src_image.cols, cv::BORDER_CONSTANT,
00124 cv::Scalar::all(0));
00125
00126 cv::Mat planes[] = { cv::Mat_<float>(padded), cv::Mat::zeros(padded.size(), CV_32F) };
00127 cv::Mat complex_image;
00128 cv::merge(planes, 2, complex_image);
00129 cv::dft(complex_image, complex_image);
00130
00131
00132
00133 cv::split(complex_image, planes);
00134 cv::magnitude(planes[0], planes[1], planes[0]);
00135 cv::Mat magnitude_image = planes[0];
00136 magnitude_image += cv::Scalar::all(1);
00137 cv::log(magnitude_image, magnitude_image);
00138
00139
00140 magnitude_image = magnitude_image(cv::Rect(0, 0, magnitude_image.cols & -2, magnitude_image.rows & -2));
00141
00142 int cx = magnitude_image.cols / 2;
00143 int cy = magnitude_image.rows / 2;
00144
00145 cv::Mat q0(magnitude_image, cv::Rect(0, 0, cx, cy));
00146 cv::Mat q1(magnitude_image, cv::Rect(cx, 0, cx, cy));
00147 cv::Mat q2(magnitude_image, cv::Rect(0, cy, cx, cy));
00148 cv::Mat q3(magnitude_image, cv::Rect(cx, cy, cx, cy));
00149
00150 cv::Mat tmp;
00151 q0.copyTo(tmp);
00152 q3.copyTo(q0);
00153 tmp.copyTo(q3);
00154
00155 q1.copyTo(tmp);
00156 q2.copyTo(q1);
00157 tmp.copyTo(q2);
00158 cv::normalize(magnitude_image, magnitude_image, 0, 255, cv::NORM_MINMAX);
00159
00160 cv::Mat result_image = cv::Mat::zeros(magnitude_image.rows, magnitude_image.cols, CV_8UC1);
00161 for (int i = 0; i < magnitude_image.rows; ++i)
00162 {
00163 unsigned char* result_data = result_image.ptr<unsigned char>(i);
00164 float* magnitude_data = magnitude_image.ptr<float>(i);
00165 for (int j = 0; j < magnitude_image.cols; ++j)
00166 {
00167 *result_data++ = (unsigned char)(*magnitude_data++);
00168 }
00169 }
00170
00171 if (debug_view_)
00172 {
00173 cv::imshow(window_name_, result_image);
00174 int c = cv::waitKey(1);
00175 }
00176 img_pub_.publish(
00177 cv_bridge::CvImage(image_msg->header, sensor_msgs::image_encodings::MONO8, result_image).toImageMsg());
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_ = image_msg->header.stamp;
00185 }
00186
00187 public:
00188 virtual void onInit()
00189 {
00190 Nodelet::onInit();
00191 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00192 pnh_->param("queue_size", queue_size_, 1);
00193 pnh_->param("debug_view", debug_view_, false);
00194
00195 if (debug_view_)
00196 {
00197 always_subscribe_ = true;
00198 }
00199 prev_stamp_ = ros::Time(0, 0);
00200
00201 window_name_ = "Discrete Fourier Transform Demo";
00202
00203 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00204 dynamic_reconfigure::Server<Config>::CallbackType f =
00205 boost::bind(&DiscreteFourierTransformNodelet::reconfigureCallback, this, _1, _2);
00206 reconfigure_server_->setCallback(f);
00207
00208 img_pub_ = advertiseImage(*pnh_, "image", 1);
00209 onInitPostProcess();
00210 }
00211 };
00212 }
00213
00214 namespace discrete_fourier_transform
00215 {
00216 class DiscreteFourierTransformNodelet : public opencv_apps::DiscreteFourierTransformNodelet
00217 {
00218 public:
00219 virtual void onInit()
00220 {
00221 ROS_WARN("DeprecationWarning: Nodelet discrete_fourier_transform/discrete_fourier_transform is deprecated, "
00222 "and renamed to opencv_apps/discrete_fourier_transform.");
00223 opencv_apps::DiscreteFourierTransformNodelet::onInit();
00224 }
00225 };
00226 }
00227
00228 #include <pluginlib/class_list_macros.h>
00229 PLUGINLIB_EXPORT_CLASS(opencv_apps::DiscreteFourierTransformNodelet, nodelet::Nodelet);
00230 PLUGINLIB_EXPORT_CLASS(discrete_fourier_transform::DiscreteFourierTransformNodelet, nodelet::Nodelet);