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 opencv_apps
00058 {
00059 class SimpleFlowNodelet : public opencv_apps::Nodelet
00060 {
00061   image_transport::Publisher img_pub_;
00062   image_transport::Subscriber img_sub_;
00063   image_transport::CameraSubscriber cam_sub_;
00064   ros::Publisher msg_pub_;
00065 
00066   boost::shared_ptr<image_transport::ImageTransport> it_;
00067 
00068   typedef opencv_apps::SimpleFlowConfig Config;
00069   typedef dynamic_reconfigure::Server<Config> ReconfigureServer;
00070   Config config_;
00071   boost::shared_ptr<ReconfigureServer> reconfigure_server_;
00072 
00073   int queue_size_;
00074   bool debug_view_;
00075   int subscriber_count_;
00076   ros::Time prev_stamp_;
00077 
00078   std::string window_name_;
00079   static bool need_config_update_;
00080   int scale_;
00081 
00082   cv::Mat gray, prevGray;
00083 
00084   void reconfigureCallback(Config& new_config, uint32_t level)
00085   {
00086     config_ = new_config;
00087     scale_ = config_.scale;
00088   }
00089 
00090   const std::string& frameWithDefault(const std::string& frame, const std::string& image_frame)
00091   {
00092     if (frame.empty())
00093       return image_frame;
00094     return frame;
00095   }
00096 
00097   void imageCallbackWithInfo(const sensor_msgs::ImageConstPtr& msg, const sensor_msgs::CameraInfoConstPtr& cam_info)
00098   {
00099     doWork(msg, cam_info->header.frame_id);
00100   }
00101 
00102   void imageCallback(const sensor_msgs::ImageConstPtr& msg)
00103   {
00104     doWork(msg, msg->header.frame_id);
00105   }
00106 
00107   static void trackbarCallback(int /*unused*/, void* /*unused*/)
00108   {
00109     need_config_update_ = true;
00110   }
00111 
00112   void doWork(const sensor_msgs::ImageConstPtr& msg, const std::string& input_frame_from_msg)
00113   {
00114     // Work on the image.
00115     try
00116     {
00117       // Convert the image into something opencv can handle.
00118       cv::Mat frame_src = cv_bridge::toCvShare(msg, sensor_msgs::image_encodings::BGR8)->image;
00119 
00121       cv::Mat frame;
00122       if (frame_src.channels() > 1)
00123       {
00124         frame = frame_src;
00125       }
00126       else
00127       {
00128         cv::cvtColor(frame_src, frame, cv::COLOR_GRAY2BGR);
00129       }
00130 
00131       cv::resize(frame, gray, cv::Size(frame.cols / (double)MAX(1, scale_), frame.rows / (double)MAX(1, scale_)), 0, 0,
00132                  CV_INTER_AREA);
00133       if (prevGray.empty())
00134         gray.copyTo(prevGray);
00135 
00136       if (gray.rows != prevGray.rows && gray.cols != prevGray.cols)
00137       {
00138         NODELET_WARN("Images should be of equal sizes");
00139         gray.copyTo(prevGray);
00140       }
00141 
00142       if (frame.type() != 16)
00143       {
00144         NODELET_ERROR("Images should be of equal type CV_8UC3");
00145       }
00146       // Messages
00147       opencv_apps::FlowArrayStamped flows_msg;
00148       flows_msg.header = msg->header;
00149 
00150       // Do the work
00151       cv::Mat flow;
00152 
00153       if (debug_view_)
00154       {
00155         cv::namedWindow(window_name_, cv::WINDOW_AUTOSIZE);
00156         cv::createTrackbar("Scale", window_name_, &scale_, 24, trackbarCallback);
00157         if (need_config_update_)
00158         {
00159           config_.scale = scale_;
00160           reconfigure_server_->updateConfig(config_);
00161           need_config_update_ = false;
00162         }
00163       }
00164 
00165       float start = (float)cv::getTickCount();
00166 #if CV_MAJOR_VERSION == 3
00167       cv::optflow::calcOpticalFlowSF(gray, prevGray,
00168 #else
00169       cv::calcOpticalFlowSF(gray, prevGray,
00170 #endif
00171                                      flow, 3, 2, 4, 4.1, 25.5, 18, 55.0, 25.5, 0.35, 18, 55.0, 25.5, 10);
00172       NODELET_INFO("calcOpticalFlowSF : %lf sec", (cv::getTickCount() - start) / cv::getTickFrequency());
00173 
00174       // writeOpticalFlowToFile(flow, file);
00175       int cols = flow.cols;
00176       int rows = flow.rows;
00177       double scale_col = frame.cols / (double)flow.cols;
00178       double scale_row = frame.rows / (double)flow.rows;
00179 
00180       for (int i = 0; i < rows; ++i)
00181       {
00182         for (int j = 0; j < cols; ++j)
00183         {
00184           cv::Vec2f flow_at_point = flow.at<cv::Vec2f>(i, j);
00185           cv::line(frame, cv::Point(scale_col * j, scale_row * i),
00186                    cv::Point(scale_col * (j + flow_at_point[0]), scale_row * (i + flow_at_point[1])),
00187                    cv::Scalar(0, 255, 0), 1, 8, 0);
00188 
00189           opencv_apps::Flow flow_msg;
00190           opencv_apps::Point2D point_msg;
00191           opencv_apps::Point2D velocity_msg;
00192           point_msg.x = scale_col * j;
00193           point_msg.y = scale_row * i;
00194           velocity_msg.x = scale_col * flow_at_point[0];
00195           velocity_msg.y = scale_row * flow_at_point[1];
00196           flow_msg.point = point_msg;
00197           flow_msg.velocity = velocity_msg;
00198           flows_msg.flow.push_back(flow_msg);
00199         }
00200       }
00201 
00202       // cv::cvtColor( frame, src_gray, cv::COLOR_BGR2GRAY );
00204       // Canny( src_gray, edges, 50, 200, 3 );
00205 
00206       //-- Show what you got
00207       if (debug_view_)
00208       {
00209         cv::imshow(window_name_, frame);
00210         int c = cv::waitKey(1);
00211       }
00212 
00213       cv::swap(prevGray, gray);
00214       // Publish the image.
00215       sensor_msgs::Image::Ptr out_img = cv_bridge::CvImage(msg->header, "bgr8", frame).toImageMsg();
00216       img_pub_.publish(out_img);
00217       msg_pub_.publish(flows_msg);
00218     }
00219     catch (cv::Exception& e)
00220     {
00221       NODELET_ERROR("Image processing error: %s %s %s %i", e.err.c_str(), e.func.c_str(), e.file.c_str(), e.line);
00222     }
00223 
00224     prev_stamp_ = msg->header.stamp;
00225   }
00226 
00227   void subscribe()  // NOLINT(modernize-use-override)
00228   {
00229     NODELET_DEBUG("Subscribing to image topic.");
00230     if (config_.use_camera_info)
00231       cam_sub_ = it_->subscribeCamera("image", queue_size_, &SimpleFlowNodelet::imageCallbackWithInfo, this);
00232     else
00233       img_sub_ = it_->subscribe("image", queue_size_, &SimpleFlowNodelet::imageCallback, this);
00234   }
00235 
00236   void unsubscribe()  // NOLINT(modernize-use-override)
00237   {
00238     NODELET_DEBUG("Unsubscribing from image topic.");
00239     img_sub_.shutdown();
00240     cam_sub_.shutdown();
00241   }
00242 
00243 public:
00244   virtual void onInit()  // NOLINT(modernize-use-override)
00245   {
00246     Nodelet::onInit();
00247     it_ = boost::shared_ptr<image_transport::ImageTransport>(new image_transport::ImageTransport(*nh_));
00248 
00249     pnh_->param("queue_size", queue_size_, 3);
00250     pnh_->param("debug_view", debug_view_, false);
00251     if (debug_view_)
00252     {
00253       always_subscribe_ = true;
00254     }
00255     prev_stamp_ = ros::Time(0, 0);
00256 
00257     window_name_ = "simpleflow_demo";
00258     scale_ = 4.0;
00259 
00260     reconfigure_server_ = boost::make_shared<dynamic_reconfigure::Server<Config> >(*pnh_);
00261     dynamic_reconfigure::Server<Config>::CallbackType f =
00262         boost::bind(&SimpleFlowNodelet::reconfigureCallback, this, _1, _2);
00263     reconfigure_server_->setCallback(f);
00264 
00265     img_pub_ = advertiseImage(*pnh_, "image", 1);
00266     msg_pub_ = advertise<opencv_apps::FlowArrayStamped>(*pnh_, "flows", 1);
00267 
00268     onInitPostProcess();
00269   }
00270 };
00271 bool SimpleFlowNodelet::need_config_update_ = false;
00272 }  // namespace opencv_apps
00273 
00274 namespace simple_flow
00275 {
00276 class SimpleFlowNodelet : public opencv_apps::SimpleFlowNodelet
00277 {
00278 public:
00279   virtual void onInit()  // NOLINT(modernize-use-override)
00280   {
00281     ROS_WARN("DeprecationWarning: Nodelet simple_flow/simple_flow is deprecated, "
00282              "and renamed to opencv_apps/simple_flow.");
00283     opencv_apps::SimpleFlowNodelet::onInit();
00284   }
00285 };
00286 }  // namespace simple_flow
00287 
00288 #include <pluginlib/class_list_macros.h>
00289 PLUGINLIB_EXPORT_CLASS(opencv_apps::SimpleFlowNodelet, nodelet::Nodelet);
00290 PLUGINLIB_EXPORT_CLASS(simple_flow::SimpleFlowNodelet, nodelet::Nodelet);


opencv_apps
Author(s): Kei Okada
autogenerated on Mon Apr 22 2019 02:18:26