44 #include "opencv2/core/core.hpp"
45 #include "opencv2/imgproc/imgproc.hpp"
46 #include "opencv2/highgui/highgui.hpp"
49 #include "opencv_apps/DiscreteFourierTransformConfig.h"
51 #include <dynamic_reconfigure/server.h>
63 typedef opencv_apps::DiscreteFourierTransformConfig
Config;
76 void imageCallbackWithInfo(
const sensor_msgs::ImageConstPtr& msg,
const sensor_msgs::CameraInfoConstPtr& cam_info)
78 doWork(msg, cam_info->header.frame_id);
83 doWork(msg, msg->header.frame_id);
105 boost::mutex::scoped_lock lock(
mutex_);
109 void doWork(
const sensor_msgs::Image::ConstPtr& image_msg,
const std::string& input_frame_from_msg)
115 if (src_image.channels() > 1)
117 cv::cvtColor(src_image, src_image, CV_BGR2GRAY);
121 int m = cv::getOptimalDFTSize(src_image.rows);
122 int n = cv::getOptimalDFTSize(src_image.cols);
123 cv::copyMakeBorder(src_image, padded, 0, m - src_image.rows, 0, n - src_image.cols, cv::BORDER_CONSTANT,
126 cv::Mat planes[] = { cv::Mat_<float>(padded), cv::Mat::zeros(padded.size(), CV_32F) };
127 cv::Mat complex_image;
128 cv::merge(planes, 2, complex_image);
129 cv::dft(complex_image, complex_image);
133 cv::split(complex_image, planes);
134 cv::magnitude(planes[0], planes[1], planes[0]);
135 cv::Mat magnitude_image = planes[0];
136 magnitude_image += cv::Scalar::all(1);
137 cv::log(magnitude_image, magnitude_image);
140 magnitude_image = magnitude_image(cv::Rect(0, 0, magnitude_image.cols & -2, magnitude_image.rows & -2));
142 int cx = magnitude_image.cols / 2;
143 int cy = magnitude_image.rows / 2;
145 cv::Mat q0(magnitude_image, cv::Rect(0, 0, cx, cy));
146 cv::Mat q1(magnitude_image, cv::Rect(cx, 0, cx, cy));
147 cv::Mat q2(magnitude_image, cv::Rect(0, cy, cx, cy));
148 cv::Mat q3(magnitude_image, cv::Rect(cx, cy, cx, cy));
158 cv::normalize(magnitude_image, magnitude_image, 0, 255, cv::NORM_MINMAX);
160 cv::Mat result_image = cv::Mat::zeros(magnitude_image.rows, magnitude_image.cols, CV_8UC1);
161 for (
int i = 0; i < magnitude_image.rows; ++i)
163 unsigned char* result_data = result_image.ptr<
unsigned char>(i);
164 float* magnitude_data = magnitude_image.ptr<
float>(i);
165 for (
int j = 0; j < magnitude_image.cols; ++j)
167 *result_data++ = (
unsigned char)(*magnitude_data++);
174 int c = cv::waitKey(1);
179 catch (cv::Exception& e)
181 NODELET_ERROR(
"Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
204 dynamic_reconfigure::Server<Config>::CallbackType
f = boost::bind(
221 ROS_WARN(
"DeprecationWarning: Nodelet discrete_fourier_transform/discrete_fourier_transform is deprecated, "
222 "and renamed to opencv_apps/discrete_fourier_transform.");
228 #ifdef USE_PLUGINLIB_CLASS_LIST_MACROS_H