flow_velocity_thresholding.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2017, JSK Lab
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/o2r other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the JSK Lab 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 #include <boost/assign.hpp>
00036 #include <boost/tuple/tuple.hpp>
00037 #include <jsk_topic_tools/log_utils.h>
00038 #include <jsk_recognition_utils/cv_utils.h>
00039 #include <opencv2/opencv.hpp>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <cv_bridge/cv_bridge.h>
00042 #include <Eigen/Dense>
00043 #include "jsk_perception/flow_velocity_thresholding.h"
00044 
00045 namespace jsk_perception
00046 {
00047   void FlowVelocityThresholding::onInit()
00048   {
00049     DiagnosticNodelet::onInit();
00050     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00051     dynamic_reconfigure::Server<Config>::CallbackType f =
00052       boost::bind (&FlowVelocityThresholding::configCallback, this, _1, _2);
00053     srv_->setCallback (f);
00054     pnh_->param("approximate_sync", approximate_sync_, false);
00055     pnh_->param("queue_size", queue_size_, 100);
00056     pnh_->param("use_camera_info", use_camera_info_, true);
00057     pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00058     onInitPostProcess();
00059   }
00060 
00061   void FlowVelocityThresholding::configCallback(
00062     Config &config, uint32_t level)
00063   {
00064     boost::mutex::scoped_lock lock(mutex_);
00065     threshold_ = config.threshold;
00066     window_size_ = config.window_size;
00067   }
00068 
00069   void FlowVelocityThresholding::subscribe()
00070   {
00071     sub_flow_.subscribe(*pnh_, "input/flows", 1);
00072     ros::V_string names = boost::assign::list_of("~input/flows");
00073     if (use_camera_info_)
00074     {
00075       sub_info_.subscribe(*pnh_, "input/camera_info", 1);
00076       if (approximate_sync_) {
00077         async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
00078         async_->connectInput(sub_flow_, sub_info_);
00079         async_->registerCallback(boost::bind(&FlowVelocityThresholding::callback, this, _1, _2));
00080       }
00081       else {
00082         sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
00083         sync_->connectInput(sub_flow_, sub_info_);
00084         sync_->registerCallback(boost::bind(&FlowVelocityThresholding::callback, this, _1, _2));
00085       }
00086       names.push_back("~input/camera_info");
00087     }
00088     else
00089     {
00090       if (pnh_->hasParam("image_height") && pnh_->hasParam("image_width"))
00091       {
00092         pnh_->getParam("image_height", image_height_);
00093         pnh_->getParam("image_width", image_width_);
00094         sub_flow_.registerCallback(&FlowVelocityThresholding::callback, this);
00095       }
00096       else
00097       {
00098         ROS_FATAL("Rosparam ~image_height and ~image_width must be set if ~use_camera_info=false");
00099       }
00100     }
00101     jsk_topic_tools::warnNoRemap(names);
00102   }
00103 
00104   void FlowVelocityThresholding::unsubscribe()
00105   {
00106     sub_flow_.unsubscribe();
00107     sub_info_.unsubscribe();
00108   }
00109 
00110   void FlowVelocityThresholding::callback(
00111     const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg)
00112   {
00113     process(flow_msg, image_height_, image_width_);
00114   }
00115 
00116   void FlowVelocityThresholding::callback(
00117     const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg,
00118     const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00119   {
00120     process(flow_msg, info_msg->height, info_msg->width);
00121   }
00122 
00123   void FlowVelocityThresholding::process(
00124     const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg,
00125     const int image_height,
00126     const int image_width)
00127   {
00128     vital_checker_->poke();
00129 
00130     cv::Mat mask = cv::Mat::zeros(image_height, image_width, CV_8UC1);
00131 
00132     for (size_t i=0; i<flow_msg->flow.size(); i++)
00133     {
00134       Eigen::Vector2d vel;
00135       vel(0) = flow_msg->flow[i].velocity.x;
00136       vel(1) = flow_msg->flow[i].velocity.y;
00137       if (vel.norm() > threshold_) {
00138         cv::Point center = cv::Point(flow_msg->flow[i].point.x, flow_msg->flow[i].point.y);
00139         cv::rectangle(
00140           mask,
00141           center - cv::Point(window_size_ / 2, window_size_ / 2),
00142           center + cv::Point(window_size_ / 2, window_size_ / 2),
00143           cv::Scalar(255),
00144           CV_FILLED);
00145       }
00146     }
00147 
00148     pub_.publish(cv_bridge::CvImage(
00149                     flow_msg->header,
00150                     sensor_msgs::image_encodings::MONO8,
00151                     mask).toImageMsg());
00152   }
00153 }  // namespace jsk_perception
00154 
00155 #include <pluginlib/class_list_macros.h>
00156 PLUGINLIB_EXPORT_CLASS(jsk_perception::FlowVelocityThresholding, nodelet::Nodelet);


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Tue Jul 2 2019 19:41:07