flow_velocity_thresholding.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, JSK Lab
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/o2r other materials provided
16  * with the distribution.
17  * * Neither the name of the JSK Lab nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <boost/assign.hpp>
36 #include <boost/tuple/tuple.hpp>
39 #include <opencv2/opencv.hpp>
41 #include <cv_bridge/cv_bridge.h>
42 #include <Eigen/Dense>
44 
45 namespace jsk_perception
46 {
48  {
49  DiagnosticNodelet::onInit();
50  srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51  dynamic_reconfigure::Server<Config>::CallbackType f =
52  boost::bind (&FlowVelocityThresholding::configCallback, this, _1, _2);
53  srv_->setCallback (f);
54  pnh_->param("approximate_sync", approximate_sync_, false);
55  pnh_->param("queue_size", queue_size_, 100);
56  pnh_->param("use_camera_info", use_camera_info_, true);
57  pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
59  }
60 
62  Config &config, uint32_t level)
63  {
64  boost::mutex::scoped_lock lock(mutex_);
65  threshold_ = config.threshold;
66  window_size_ = config.window_size;
67  }
68 
70  {
71  sub_flow_.subscribe(*pnh_, "input/flows", 1);
72  ros::V_string names = boost::assign::list_of("~input/flows");
73  if (use_camera_info_)
74  {
75  sub_info_.subscribe(*pnh_, "input/camera_info", 1);
76  if (approximate_sync_) {
77  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
78  async_->connectInput(sub_flow_, sub_info_);
79  async_->registerCallback(boost::bind(&FlowVelocityThresholding::callback, this, _1, _2));
80  }
81  else {
82  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
83  sync_->connectInput(sub_flow_, sub_info_);
84  sync_->registerCallback(boost::bind(&FlowVelocityThresholding::callback, this, _1, _2));
85  }
86  names.push_back("~input/camera_info");
87  }
88  else
89  {
90  if (pnh_->hasParam("image_height") && pnh_->hasParam("image_width"))
91  {
92  pnh_->getParam("image_height", image_height_);
93  pnh_->getParam("image_width", image_width_);
95  }
96  else
97  {
98  ROS_FATAL("Rosparam ~image_height and ~image_width must be set if ~use_camera_info=false");
99  }
100  }
102  }
103 
105  {
108  }
109 
111  const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg)
112  {
113  process(flow_msg, image_height_, image_width_);
114  }
115 
117  const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg,
118  const sensor_msgs::CameraInfo::ConstPtr& info_msg)
119  {
120  process(flow_msg, info_msg->height, info_msg->width);
121  }
122 
124  const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg,
125  const int image_height,
126  const int image_width)
127  {
128  vital_checker_->poke();
129 
130  cv::Mat mask = cv::Mat::zeros(image_height, image_width, CV_8UC1);
131 
132  for (size_t i=0; i<flow_msg->flow.size(); i++)
133  {
134  Eigen::Vector2d vel;
135  vel(0) = flow_msg->flow[i].velocity.x;
136  vel(1) = flow_msg->flow[i].velocity.y;
137  if (vel.norm() > threshold_) {
138  cv::Point center = cv::Point(flow_msg->flow[i].point.x, flow_msg->flow[i].point.y);
139  cv::rectangle(
140  mask,
141  center - cv::Point(window_size_ / 2, window_size_ / 2),
142  center + cv::Point(window_size_ / 2, window_size_ / 2),
143  cv::Scalar(255),
144  CV_FILLED);
145  }
146  }
147 
149  flow_msg->header,
151  mask).toImageMsg());
152  }
153 } // namespace jsk_perception
154 
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
f
#define ROS_FATAL(...)
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(jsk_perception::FlowVelocityThresholding, nodelet::Nodelet)
jsk_perception::FlowVelocityThresholdingConfig Config
message_filters::Subscriber< opencv_apps::FlowArrayStamped > sub_flow_
virtual void configCallback(Config &config, uint32_t level)
std::vector< std::string > V_string
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
boost::shared_ptr< ros::NodeHandle > pnh_
bool warnNoRemap(const std::vector< std::string > names)
virtual void callback(const opencv_apps::FlowArrayStamped::ConstPtr &flows_msg)
jsk_topic_tools::VitalChecker::Ptr vital_checker_
mutex_t * lock
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
virtual void process(const opencv_apps::FlowArrayStamped::ConstPtr &flows_msg, const int image_height, const int image_width)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
sensor_msgs::ImagePtr toImageMsg() const
Connection registerCallback(const C &callback)
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Mon May 3 2021 03:03:27