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