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 #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 }
00154
00155 #include <pluginlib/class_list_macros.h>
00156 PLUGINLIB_EXPORT_CLASS(jsk_perception::FlowVelocityThresholding, nodelet::Nodelet);