simple_flow_nodelet.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 *
00004 *  Copyright (c) 2014, Kei Okada.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Kei Okada nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 // https://github.com/Itseez/opencv/blob/2.4/samples/cpp/simpleflow_demo.cpp
00040 #include <ros/ros.h>
00041 #include "opencv_apps/nodelet.h"
00042 #include <image_transport/image_transport.h>
00043 #include <cv_bridge/cv_bridge.h>
00044 #include <sensor_msgs/image_encodings.h>
00045 
00046 #include <opencv2/highgui/highgui.hpp>
00047 #include <opencv2/imgproc/imgproc.hpp>
00048 #include <opencv2/video/tracking.hpp>
00049 #if CV_MAJOR_VERSION == 3
00050 #include <opencv2/optflow.hpp>
00051 #endif
00052 
00053 #include <dynamic_reconfigure/server.h>
00054 #include "opencv_apps/SimpleFlowConfig.h"
00055 #include "opencv_apps/FlowArrayStamped.h"
00056 
00057 namespace simple_flow {
00058 class SimpleFlowNodelet : public opencv_apps::Nodelet
00059 {
00060   image_transport::Publisher img_pub_;
00061   image_transport::Subscriber img_sub_;
00062   image_transport::CameraSubscriber cam_sub_;
00063   ros::Publisher msg_pub_;
00064 
00065   boost::shared_ptr<image_transport::ImageTransport> it_;
00066 
00067   typedef simple_flow::SimpleFlowConfig Config;
00068   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00069   Config config_;
00070   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00071 
00072   bool debug_view_;
00073   int subscriber_count_;
00074   ros::Time prev_stamp_;
00075 
00076   std::string window_name_;
00077   static bool need_config_update_;
00078   int scale_;
00079   
00080   cv::Mat gray, prevGray;
00081 
00082   void reconfigureCallback(Config &new_config, uint32_t level)
00083   {
00084     config_ = new_config;
00085     scale_ = config_.scale;
00086   }
00087 
00088   const std::string &frameWithDefault(const std::string &frame, const std::string &image_frame)
00089   {
00090     if (frame.empty())
00091       return image_frame;
00092     return frame;
00093   }
00094 
00095   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00096   {
00097     do_work(msg, cam_info->header.frame_id);
00098   }
00099   
00100   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00101   {
00102     do_work(msg, msg->header.frame_id);
00103   }
00104 
00105   static void trackbarCallback( int, void* )
00106   {
00107     need_config_update_ = true;
00108   }
00109 
00110   void do_work(const sensor_msgs::ImageConstPtr& msg, const std::string input_frame_from_msg)
00111   {
00112     // Work on the image.
00113     try
00114     {
00115       // Convert the image into something opencv can handle.
00116       cv::Mat frame_src = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00117 
00119       cv::Mat frame;
00120       if ( frame_src.channels() > 1 ) {
00121         frame = frame_src;
00122       } else {
00123         cv::cvtColor( frame_src, frame, cv::COLOR_GRAY2BGR );
00124       }
00125 
00126       cv::resize(frame, gray, cv::Size(frame.cols/(double)MAX(1,scale_), frame.rows/(double)MAX(1,scale_)), 0, 0, CV_INTER_AREA);
00127       if(prevGray.empty())
00128         gray.copyTo(prevGray);
00129 
00130       if (gray.rows != prevGray.rows && gray.cols != prevGray.cols) {
00131         NODELET_WARN("Images should be of equal sizes");
00132         gray.copyTo(prevGray);
00133       }
00134 
00135       if (frame.type() != 16) {
00136         NODELET_ERROR("Images should be of equal type CV_8UC3");
00137       }
00138       // Messages
00139       opencv_apps::FlowArrayStamped flows_msg;
00140       flows_msg.header = msg->header;
00141 
00142       // Do the work
00143       cv::Mat flow;
00144 
00145       if( debug_view_) {
00146         cv::namedWindow( window_name_, cv::WINDOW_AUTOSIZE );
00147         cv::createTrackbar( "Scale", window_name_, &scale_, 24, trackbarCallback);
00148         if (need_config_update_) {
00149           config_.scale = scale_;
00150           reconfigure_server_->updateConfig(config_);
00151           need_config_update_ = false;
00152         }
00153       }
00154 
00155       float start = (float)cv::getTickCount();
00156 #if CV_MAJOR_VERSION == 3
00157       cv::optflow::calcOpticalFlowSF(gray, prevGray,
00158 #else
00159       cv::calcOpticalFlowSF(gray, prevGray,
00160 #endif
00161                             flow,
00162                             3, 2, 4, 4.1, 25.5, 18, 55.0, 25.5, 0.35, 18, 55.0, 25.5, 10);
00163       NODELET_INFO("calcOpticalFlowSF : %lf sec", (cv::getTickCount() - start) / cv::getTickFrequency());
00164 
00165       //writeOpticalFlowToFile(flow, file);
00166       int cols = flow.cols;
00167       int rows = flow.rows;
00168       double scale_col = frame.cols/(double)flow.cols;
00169       double scale_row = frame.rows/(double)flow.rows;
00170 
00171 
00172       for (int i= 0; i < rows; ++i) {
00173         for (int j = 0; j < cols; ++j) {
00174           cv::Vec2f flow_at_point = flow.at<cv::Vec2f>(i, j);
00175           cv::line(frame, cv::Point(scale_col*j, scale_row*i), cv::Point(scale_col*(j+flow_at_point[0]), scale_row*(i+flow_at_point[1])), cv::Scalar(0,255,0), 1, 8, 0 );
00176 
00177           opencv_apps::Flow flow_msg;
00178           opencv_apps::Point2D point_msg;
00179           opencv_apps::Point2D velocity_msg;
00180           point_msg.x = scale_col*j;
00181           point_msg.y = scale_row*i;
00182           velocity_msg.x = scale_col*flow_at_point[0];
00183           velocity_msg.y = scale_row*flow_at_point[1];
00184           flow_msg.point = point_msg;
00185           flow_msg.velocity = velocity_msg;
00186           flows_msg.flow.push_back(flow_msg);
00187         }
00188       }
00189 
00190       //cv::cvtColor( frame, src_gray, cv::COLOR_BGR2GRAY );
00192       //Canny( src_gray, edges, 50, 200, 3 );
00193 
00194       //-- Show what you got
00195       if ( debug_view_) {
00196         cv::imshow( window_name_, frame );
00197         int c = cv::waitKey(1);
00198       }
00199 
00200       cv::swap(prevGray, gray);
00201       // Publish the image.
00202       sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", frame).toImageMsg();
00203       img_pub_.publish(out_img);
00204       msg_pub_.publish(flows_msg);
00205     }
00206     catch (cv::Exception &e)
00207     {
00208       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00209     }
00210 
00211     prev_stamp_ = msg->header.stamp;
00212   }
00213 
00214   void subscribe()
00215   {
00216     NODELET_DEBUG("Subscribing to image topic.");
00217     if (config_.use_camera_info)
00218       cam_sub_ = it_->subscribeCamera("image", 3, &SimpleFlowNodelet::imageCallbackWithInfo, this);
00219     else
00220       img_sub_ = it_->subscribe("image", 3, &SimpleFlowNodelet::imageCallback, this);
00221   }
00222 
00223   void unsubscribe()
00224   {
00225     NODELET_DEBUG("Unsubscribing from image topic.");
00226     img_sub_.shutdown();
00227     cam_sub_.shutdown();
00228   }
00229 
00230 public:
00231   virtual void onInit()
00232   {
00233     Nodelet::onInit();
00234     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00235 
00236     pnh_->param("debug_view", debug_view_, false);
00237     if (debug_view_) {
00238       always_subscribe_ = true;
00239     }
00240     prev_stamp_ = ros::Time(0, 0);
00241 
00242     window_name_ = "simpleflow_demo";
00243     scale_ = 4.0;
00244 
00245     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00246     dynamic_reconfigure::Server<Config>::CallbackType f =
00247       boost::bind(&SimpleFlowNodelet::reconfigureCallback, this, _1, _2);
00248     reconfigure_server_->setCallback(f);
00249     
00250     img_pub_ = advertiseImage(*pnh_, "image", 1);
00251     msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*pnh_, "flows", 1);
00252 
00253     onInitPostProcess();
00254   }
00255 };
00256 bool SimpleFlowNodelet::need_config_update_ = false;
00257 }
00258 
00259 #include <pluginlib/class_list_macros.h>
00260 PLUGINLIB_EXPORT_CLASS(simple_flow::SimpleFlowNodelet, nodelet::Nodelet);


opencv_apps
Author(s): Kei Okada
autogenerated on Tue May 2 2017 02:58:59