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
00038
00039
00040
00041 #include <ros/ros.h>
00042 #include "opencv_apps/nodelet.h"
00043 #include <image_transport/image_transport.h>
00044 #include <cv_bridge/cv_bridge.h>
00045 #include <sensor_msgs/image_encodings.h>
00046
00047 #include <opencv2/highgui/highgui.hpp>
00048 #include <opencv2/imgproc/imgproc.hpp>
00049 #include <opencv2/video/tracking.hpp>
00050
00051 #include <dynamic_reconfigure/server.h>
00052 #include "opencv_apps/FBackFlowConfig.h"
00053 #include "opencv_apps/FlowArrayStamped.h"
00054
00055 namespace fback_flow {
00056 class FBackFlowNodelet : public opencv_apps::Nodelet
00057 {
00058 image_transport::Publisher img_pub_;
00059 image_transport::Subscriber img_sub_;
00060 image_transport::CameraSubscriber cam_sub_;
00061 ros::Publisher msg_pub_;
00062
00063 boost::shared_ptr<image_transport::ImageTransport> it_;
00064
00065 typedef fback_flow::FBackFlowConfig Config;
00066 typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00067 Config config_;
00068 boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00069
00070 bool debug_view_;
00071 ros::Time prev_stamp_;
00072
00073 std::string window_name_;
00074 static bool need_config_update_;
00075
00076 cv::Mat prevgray, gray, flow, cflow;
00077
00078 void reconfigureCallback(Config &new_config, uint32_t level)
00079 {
00080 config_ = new_config;
00081 }
00082
00083 const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00084 {
00085 if (frame.empty())
00086 return image_frame;
00087 return frame;
00088 }
00089
00090 void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00091 {
00092 do_work(msg, cam_info->header.frame_id);
00093 }
00094
00095 void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00096 {
00097 do_work(msg, msg->header.frame_id);
00098 }
00099
00100 static void trackbarCallback( int, void* )
00101 {
00102 need_config_update_ = true;
00103 }
00104
00105 void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00106 {
00107
00108 try
00109 {
00110
00111 cv::Mat frame = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00112
00113
00114 opencv_apps::FlowArrayStamped flows_msg;
00115 flows_msg.header = msg->header;
00116
00117 if( debug_view_) {
00118 cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00119 if (need_config_update_) {
00120 reconfigure_server_->updateConfig(config_);
00121 need_config_update_ = false;
00122 }
00123 }
00124
00125
00126 if ( frame.channels() > 1 ) {
00127 cv::cvtColor( frame, gray, cv::COLOR_BGR2GRAY );
00128 } else {
00129 frame.copyTo(gray);
00130 }
00131 if( prevgray.data )
00132 {
00133 cv::calcOpticalFlowFarneback(prevgray, gray, flow, 0.5, 3, 15, 3, 5, 1.2, 0);
00134 cv::cvtColor(prevgray, cflow, cv::COLOR_GRAY2BGR);
00135
00136 int step = 16;
00137 cv::Scalar color = cv::Scalar(0, 255, 0);
00138 for(int y = 0; y < cflow.rows; y += step)
00139 for(int x = 0; x < cflow.cols; x += step)
00140 {
00141 const cv::Point2f& fxy = flow.at<cv::Point2f>(y, x);
00142 cv::line(cflow, cv::Point(x,y), cv::Point(cvRound(x+fxy.x), cvRound(y+fxy.y)),
00143 color);
00144 cv::circle(cflow, cv::Point(x,y), 2, color, -1);
00145
00146 opencv_apps::Flow flow_msg;
00147 opencv_apps::Point2D point_msg;
00148 opencv_apps::Point2D velocity_msg;
00149 point_msg.x = x;
00150 point_msg.y = y;
00151 velocity_msg.x = fxy.x;
00152 velocity_msg.y = fxy.y;
00153 flow_msg.point = point_msg;
00154 flow_msg.velocity = velocity_msg;
00155 flows_msg.flow.push_back(flow_msg);
00156 }
00157 }
00158
00159 std::swap(prevgray, gray);
00160
00161
00162 if( debug_view_) {
00163 cv::imshow( window_name_, cflow );
00164 int c = cv::waitKey(1);
00165 }
00166
00167
00168
00169 sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", cflow).toImageMsg();
00170 img_pub_.publish(out_img);
00171 msg_pub_.publish(flows_msg);
00172 }
00173 catch (cv::Exception &e)
00174 {
00175 NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00176 }
00177
00178 prev_stamp_ = msg->header.stamp;
00179 }
00180
00181 void subscribe()
00182 {
00183 NODELET_DEBUG("Subscribing to image topic.");
00184 if (config_.use_camera_info)
00185 cam_sub_ = it_->subscribeCamera("image", 3, &FBackFlowNodelet::imageCallbackWithInfo, this);
00186 else
00187 img_sub_ = it_->subscribe("image", 3, &FBackFlowNodelet::imageCallback, this);
00188 }
00189
00190 void unsubscribe()
00191 {
00192 NODELET_DEBUG("Unsubscribing from image topic.");
00193 img_sub_.shutdown();
00194 cam_sub_.shutdown();
00195 }
00196
00197 public:
00198 virtual void onInit()
00199 {
00200 Nodelet::onInit();
00201 it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00202
00203 pnh_->param("debug_view", debug_view_, false);
00204 if (debug_view_) {
00205 always_subscribe_ = true;
00206 }
00207 prev_stamp_ = ros::Time(0, 0);
00208
00209 window_name_ = "flow";
00210
00211 reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00212 dynamic_reconfigure::Server<Config>::CallbackType f =
00213 boost::bind(&FBackFlowNodelet::reconfigureCallback, this, _1, _2);
00214 reconfigure_server_->setCallback(f);
00215
00216 img_pub_ = advertiseImage(*pnh_, "image", 1);
00217 msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*pnh_, "flows", 1);
00218
00219 onInitPostProcess();
00220 }
00221 };
00222 bool FBackFlowNodelet::need_config_update_ = false;
00223 }
00224
00225 #include <pluginlib/class_list_macros.h>
00226 PLUGINLIB_EXPORT_CLASS(fback_flow::FBackFlowNodelet, nodelet::Nodelet);