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