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