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
00037 #include <ros/ros.h>
00038 #include "opencv_apps/nodelet.h"
00039 #include <image_transport/image_transport.h>
00040 #include <cv_bridge/cv_bridge.h>
00041 #include <sensor_msgs/image_encodings.h>
00042
00043 #include <opencv2/highgui/highgui.hpp>
00044 #include <opencv2/imgproc/imgproc.hpp>
00045
00046 #include <dynamic_reconfigure/server.h>
00047 #include "opencv_apps/PhaseCorrConfig.h"
00048 #include "opencv_apps/Point2DStamped.h"
00049
00050 namespace opencv_apps
00051 {
00052 class PhaseCorrNodelet : public opencv_apps::Nodelet
00053 {
00054 image_transport::Publisher img_pub_;
00055 image_transport::Subscriber img_sub_;
00056 image_transport::CameraSubscriber cam_sub_;
00057 ros::Publisher msg_pub_;
00058
00059 boost::shared_ptr<image_transport::ImageTransport> it_;
00060
00061 typedef opencv_apps::PhaseCorrConfig Config;
00062 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00063 Config config_;
00064 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00065
00066 int queue_size_;
00067 bool debug_view_;
00068 ros::Time prev_stamp_;
00069
00070 cv::Mat curr, prev, curr64f, prev64f, hann;
00071
00072 std::string window_name_;
00073 static bool need_config_update_;
00074
00075 void reconfigureCallback(Config& new_config, uint32_t level)
00076 {
00077 config_ = new_config;
00078 }
00079
00080 const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00081 {
00082 if (frame.empty())
00083 return image_frame;
00084 return frame;
00085 }
00086
00087 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00088 {
00089 doWork(msg, cam_info->header.frame_id);
00090 }
00091
00092 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00093 {
00094 doWork(msg, msg->header.frame_id);
00095 }
00096
00097 static void trackbarCallback(int , void* )
00098 {
00099 need_config_update_ = true;
00100 }
00101
00102 void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
00103 {
00104
00105 try
00106 {
00107
00108 cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00109
00110
00111 opencv_apps::Point2DStamped shift_msg;
00112 shift_msg.header = msg->header;
00113
00114
00115 if (frame.channels() > 1)
00116 {
00117 cv::cvtColor(frame, curr, cv::COLOR_BGR2GRAY);
00118 }
00119 else
00120 {
00121 curr = frame;
00122 }
00123
00124 if (debug_view_)
00125 {
00126 cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00127 if (need_config_update_)
00128 {
00129 reconfigure_server_->updateConfig(config_);
00130 need_config_update_ = false;
00131 }
00132 }
00133
00134 if (prev.empty())
00135 {
00136 prev = curr.clone();
00137 cv::createHanningWindow(hann, curr.size(), CV_64F);
00138 }
00139
00140 prev.convertTo(prev64f, CV_64F);
00141 curr.convertTo(curr64f, CV_64F);
00142
00143 cv::Point2d shift = cv::phaseCorrelate(prev64f, curr64f, hann);
00144 double radius = cv::sqrt(shift.x * shift.x + shift.y * shift.y);
00145
00146 if (radius > 0)
00147 {
00148
00149 cv::Point center(curr.cols >> 1, curr.rows >> 1);
00150 #ifndef CV_VERSION_EPOCH
00151 cv::circle(frame, center, (int)(radius * 5), cv::Scalar(0, 255, 0), 3, cv::LINE_AA);
00152 cv::line(frame, center, cv::Point(center.x + (int)(shift.x * 5), center.y + (int)(shift.y * 5)),
00153 cv::Scalar(0, 255, 0), 3, cv::LINE_AA);
00154 #else
00155 cv::circle(frame, center, (int)(radius * 5), cv::Scalar(0, 255, 0), 3, CV_AA);
00156 cv::line(frame, center, cv::Point(center.x + (int)(shift.x * 5), center.y + (int)(shift.y * 5)),
00157 cv::Scalar(0, 255, 0), 3, CV_AA);
00158 #endif
00159
00160
00161 shift_msg.point.x = shift.x;
00162 shift_msg.point.y = shift.y;
00163 }
00164
00165
00166 if (debug_view_)
00167 {
00168 cv::imshow(window_name_, frame);
00169 int c = cv::waitKey(1);
00170 }
00171
00172 prev = curr.clone();
00173
00174
00175 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, msg->encoding, frame).toImageMsg();
00176 img_pub_.publish(out_img);
00177 msg_pub_.publish(shift_msg);
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_ = msg->header.stamp;
00185 }
00186
00187 void subscribe()
00188 {
00189 NODELET_DEBUG("Subscribing to image topic.");
00190 if (config_.use_camera_info)
00191 cam_sub_ = it_->subscribeCamera("image", queue_size_, &PhaseCorrNodelet::imageCallbackWithInfo, this);
00192 else
00193 img_sub_ = it_->subscribe("image", queue_size_, &PhaseCorrNodelet::imageCallback, this);
00194 }
00195
00196 void unsubscribe()
00197 {
00198 NODELET_DEBUG("Unsubscribing from image topic.");
00199 img_sub_.shutdown();
00200 cam_sub_.shutdown();
00201 }
00202
00203 public:
00204 virtual void onInit()
00205 {
00206 Nodelet::onInit();
00207 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00208
00209 pnh_->param("queue_size", queue_size_, 3);
00210 pnh_->param("debug_view", debug_view_, false);
00211 if (debug_view_)
00212 {
00213 always_subscribe_ = true;
00214 }
00215 prev_stamp_ = ros::Time(0, 0);
00216
00217 window_name_ = "phase shift";
00218
00219 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00220 dynamic_reconfigure::Server<Config>::CallbackType f =
00221 boost::bind(&PhaseCorrNodelet::reconfigureCallback, this, _1, _2);
00222 reconfigure_server_->setCallback(f);
00223
00224 img_pub_ = advertiseImage(*pnh_, "image", 1);
00225 msg_pub_ = advertise<opencv_apps::Point2DStamped>(*pnh_, "shift", 1);
00226
00227 onInitPostProcess();
00228 }
00229 };
00230 bool PhaseCorrNodelet::need_config_update_ = false;
00231 }
00232
00233 namespace phase_corr
00234 {
00235 class PhaseCorrNodelet : public opencv_apps::PhaseCorrNodelet
00236 {
00237 public:
00238 virtual void onInit()
00239 {
00240 ROS_WARN("DeprecationWarning: Nodelet phase_corr/phase_corr is deprecated, "
00241 "and renamed to opencv_apps/phase_corr.");
00242 opencv_apps::PhaseCorrNodelet::onInit();
00243 }
00244 };
00245 }
00246
00247 #include <pluginlib/class_list_macros.h>
00248 PLUGINLIB_EXPORT_CLASS(opencv_apps::PhaseCorrNodelet, nodelet::Nodelet);
00249 PLUGINLIB_EXPORT_CLASS(phase_corr::PhaseCorrNodelet, nodelet::Nodelet);