discrete_fourier_transform_nodelet.cpp
Go to the documentation of this file.
1 // -*- coding:utf-8-unix; mode: c++; indent-tabs-mode: nil; c-basic-offset: 2; -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2016, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 // https://github.com/opencv/opencv/blob/2.4/samples/cpp/tutorial_code/core/discrete_fourier_transform/discrete_fourier_transform.cpp
43 #include <cv_bridge/cv_bridge.h>
44 #include "opencv2/core/core.hpp"
45 #include "opencv2/imgproc/imgproc.hpp"
46 #include "opencv2/highgui/highgui.hpp"
47 
48 #include "opencv_apps/nodelet.h"
49 #include "opencv_apps/DiscreteFourierTransformConfig.h"
50 
51 #include <dynamic_reconfigure/server.h>
52 
53 namespace opencv_apps
54 {
56 {
60 
62 
63  typedef opencv_apps::DiscreteFourierTransformConfig Config;
64  typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
65  Config config_;
67 
71 
72  boost::mutex mutex_;
73 
74  std::string window_name_;
75 
76  void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
77  {
78  doWork(msg, cam_info->header.frame_id);
79  }
80 
81  void imageCallback(const sensor_msgs::ImageConstPtr& msg)
82  {
83  doWork(msg, msg->header.frame_id);
84  }
85 
86  void subscribe() // NOLINT(modernize-use-override)
87  {
88  NODELET_DEBUG("Subscribing to image topic.");
89  if (config_.use_camera_info)
90  cam_sub_ =
91  it_->subscribeCamera("image", queue_size_, &DiscreteFourierTransformNodelet::imageCallbackWithInfo, this);
92  else
93  img_sub_ = it_->subscribe("image", queue_size_, &DiscreteFourierTransformNodelet::imageCallback, this);
94  }
95 
96  void unsubscribe() // NOLINT(modernize-use-override)
97  {
98  NODELET_DEBUG("Unsubscribing from image topic.");
99  img_sub_.shutdown();
100  cam_sub_.shutdown();
101  }
102 
103  void reconfigureCallback(Config& config, uint32_t level)
104  {
105  boost::mutex::scoped_lock lock(mutex_);
106  config_ = config;
107  }
108 
109  void doWork(const sensor_msgs::Image::ConstPtr& image_msg, const std::string& input_frame_from_msg)
110  {
111  // Work on the image.
112  try
113  {
114  cv::Mat src_image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
115  if (src_image.channels() > 1)
116  {
117  cv::cvtColor(src_image, src_image, CV_BGR2GRAY);
118  }
119 
120  cv::Mat padded; // expand input image to optimal size
121  int m = cv::getOptimalDFTSize(src_image.rows);
122  int n = cv::getOptimalDFTSize(src_image.cols); // on the border add zero values
123  cv::copyMakeBorder(src_image, padded, 0, m - src_image.rows, 0, n - src_image.cols, cv::BORDER_CONSTANT,
124  cv::Scalar::all(0));
125 
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); // Add to the expanded another plane with zeros
129  cv::dft(complex_image, complex_image); // this way the result may fit in the source matrix
130 
131  // compute the magnitude and switch to logarithmic scale
132  // => log(1 + sqrt(Re(DFT(I))^2 + Im(DFT(I))^2))
133  cv::split(complex_image, planes); // planes[0] = Re(DFT(I), planes[1] = Im(DFT(I))
134  cv::magnitude(planes[0], planes[1], planes[0]); // planes[0] = magnitude
135  cv::Mat magnitude_image = planes[0];
136  magnitude_image += cv::Scalar::all(1); // switch to logarithmic scale
137  cv::log(magnitude_image, magnitude_image);
138 
139  // crop the spectrum, if it has an odd number of rows or columns
140  magnitude_image = magnitude_image(cv::Rect(0, 0, magnitude_image.cols & -2, magnitude_image.rows & -2));
141  // rearrange the quadrants of Fourier imagev so that the origin is at the image center
142  int cx = magnitude_image.cols / 2;
143  int cy = magnitude_image.rows / 2;
144 
145  cv::Mat q0(magnitude_image, cv::Rect(0, 0, cx, cy)); // Top-Left - Create a ROI per quadrant
146  cv::Mat q1(magnitude_image, cv::Rect(cx, 0, cx, cy)); // Top-Right
147  cv::Mat q2(magnitude_image, cv::Rect(0, cy, cx, cy)); // Bottom-Left
148  cv::Mat q3(magnitude_image, cv::Rect(cx, cy, cx, cy)); // Bottom-Right
149 
150  cv::Mat tmp; // swap quadrants (Top-Left with Bottom-Right)
151  q0.copyTo(tmp);
152  q3.copyTo(q0);
153  tmp.copyTo(q3);
154 
155  q1.copyTo(tmp); // swap quadrant (Top-Right with Bottom-Left)
156  q2.copyTo(q1);
157  tmp.copyTo(q2);
158  cv::normalize(magnitude_image, magnitude_image, 0, 255, cv::NORM_MINMAX);
159 
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)
162  {
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)
166  {
167  *result_data++ = (unsigned char)(*magnitude_data++);
168  }
169  }
170 
171  if (debug_view_)
172  {
173  cv::imshow(window_name_, result_image);
174  int c = cv::waitKey(1);
175  }
176  img_pub_.publish(
177  cv_bridge::CvImage(image_msg->header, sensor_msgs::image_encodings::MONO8, result_image).toImageMsg());
178  }
179  catch (cv::Exception& e)
180  {
181  NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
182  }
183 
184  prev_stamp_ = image_msg->header.stamp;
185  }
186 
187 public:
188  virtual void onInit() // NOLINT(modernize-use-override)
189  {
190  Nodelet::onInit();
192  pnh_->param("queue_size", queue_size_, 1);
193  pnh_->param("debug_view", debug_view_, false);
194 
195  if (debug_view_)
196  {
197  always_subscribe_ = true;
198  }
199  prev_stamp_ = ros::Time(0, 0);
200 
201  window_name_ = "Discrete Fourier Transform Demo";
202 
203  reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
204  dynamic_reconfigure::Server<Config>::CallbackType f =
205  boost::bind(&DiscreteFourierTransformNodelet::reconfigureCallback, this, _1, _2);
206  reconfigure_server_->setCallback(f);
207 
208  img_pub_ = advertiseImage(*pnh_, "image", 1);
210  }
211 };
212 } // namespace opencv_apps
213 
215 {
217 {
218 public:
219  virtual void onInit() // NOLINT(modernize-use-override)
220  {
221  ROS_WARN("DeprecationWarning: Nodelet discrete_fourier_transform/discrete_fourier_transform is deprecated, "
222  "and renamed to opencv_apps/discrete_fourier_transform.");
224  }
225 };
226 } // namespace discrete_fourier_transform
227 
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_ERROR(...)
f
Nodelet to automatically subscribe/unsubscribe topics according to subscription of advertised topics...
Definition: nodelet.h:70
Demo code to calculate moments.
Definition: nodelet.h:48
void unsubscribe()
This method is called when publisher is unsubscribed by other nodes. Shut down subscribers in this me...
boost::shared_ptr< image_transport::ImageTransport > it_
boost::shared_ptr< ros::NodeHandle > pnh_
Shared pointer to private nodehandle.
Definition: nodelet.h:250
void subscribe()
This method is called when publisher is subscribed by other nodes. Set up subscribers in this method...
#define ROS_WARN(...)
void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr &msg, const sensor_msgs::CameraInfoConstPtr &cam_info)
bool always_subscribe_
A flag to disable watching mechanism and always subscribe input topics. It can be specified via ~alwa...
Definition: nodelet.h:273
void imageCallback(const sensor_msgs::ImageConstPtr &msg)
virtual void onInitPostProcess()
Post processing of initialization of nodelet. You need to call this method in order to use always_sub...
Definition: nodelet.cpp:57
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
Definition: nodelet.cpp:40
void publish(const sensor_msgs::Image &message) const
boost::shared_ptr< ros::NodeHandle > nh_
Shared pointer to nodehandle.
Definition: nodelet.h:245
void doWork(const sensor_msgs::Image::ConstPtr &image_msg, const std::string &input_frame_from_msg)
image_transport::Publisher advertiseImage(ros::NodeHandle &nh, const std::string &topic, int queue_size)
Advertise an image topic and watch the publisher. Publishers which are created by this method...
Definition: nodelet.h:180
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...
opencv_apps::DiscreteFourierTransformConfig Config
PLUGINLIB_EXPORT_CLASS(opencv_apps::DiscreteFourierTransformNodelet, nodelet::Nodelet)
#define NODELET_DEBUG(...)
sensor_msgs::ImagePtr toImageMsg() const
virtual void onInit()
Initialize nodehandles nh_ and pnh_. Subclass should call this method in its onInit method...


opencv_apps
Author(s): Kei Okada
autogenerated on Sat Aug 22 2020 03:35:08