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/or 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>
37 #include <jsk_topic_tools/log_utils.h>
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);
58  onInitPostProcess();
59  }
60 
62  // message_filters::Synchronizer needs to be called reset
63  // before message_filters::Subscriber is freed.
64  // Calling reset fixes the following error on shutdown of the nodelet:
65  // terminate called after throwing an instance of
66  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
67  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
68  // Also see https://github.com/ros/ros_comm/issues/720 .
69  sync_.reset();
70  async_.reset();
71  }
72 
74  Config &config, uint32_t level)
75  {
76  boost::mutex::scoped_lock lock(mutex_);
77  threshold_ = config.threshold;
78  window_size_ = config.window_size;
79  }
80 
82  {
83  sub_flow_.subscribe(*pnh_, "input/flows", 1);
84  ros::V_string names = boost::assign::list_of("~input/flows");
85  if (use_camera_info_)
86  {
87  sub_info_.subscribe(*pnh_, "input/camera_info", 1);
88  if (approximate_sync_) {
89  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
90  async_->connectInput(sub_flow_, sub_info_);
91  async_->registerCallback(boost::bind(&FlowVelocityThresholding::callback, this, _1, _2));
92  }
93  else {
94  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
95  sync_->connectInput(sub_flow_, sub_info_);
96  sync_->registerCallback(boost::bind(&FlowVelocityThresholding::callback, this, _1, _2));
97  }
98  names.push_back("~input/camera_info");
99  }
100  else
101  {
102  if (pnh_->hasParam("image_height") && pnh_->hasParam("image_width"))
103  {
104  pnh_->getParam("image_height", image_height_);
105  pnh_->getParam("image_width", image_width_);
107  }
108  else
109  {
110  ROS_FATAL("Rosparam ~image_height and ~image_width must be set if ~use_camera_info=false");
111  }
112  }
113  jsk_topic_tools::warnNoRemap(names);
114  }
115 
117  {
120  }
121 
123  const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg)
124  {
125  process(flow_msg, image_height_, image_width_);
126  }
127 
129  const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg,
130  const sensor_msgs::CameraInfo::ConstPtr& info_msg)
131  {
132  process(flow_msg, info_msg->height, info_msg->width);
133  }
134 
136  const opencv_apps::FlowArrayStamped::ConstPtr& flow_msg,
137  const int image_height,
138  const int image_width)
139  {
140  vital_checker_->poke();
141 
142  cv::Mat mask = cv::Mat::zeros(image_height, image_width, CV_8UC1);
143 
144  for (size_t i=0; i<flow_msg->flow.size(); i++)
145  {
146  Eigen::Vector2d vel;
147  vel(0) = flow_msg->flow[i].velocity.x;
148  vel(1) = flow_msg->flow[i].velocity.y;
149  if (vel.norm() > threshold_) {
150  cv::Point center = cv::Point(flow_msg->flow[i].point.x, flow_msg->flow[i].point.y);
151  cv::rectangle(
152  mask,
153  center - cv::Point(window_size_ / 2, window_size_ / 2),
154  center + cv::Point(window_size_ / 2, window_size_ / 2),
155  cv::Scalar(255),
156  CV_FILLED);
157  }
158  }
159 
161  flow_msg->header,
163  mask).toImageMsg());
164  }
165 } // namespace jsk_perception
166 
jsk_perception::FlowVelocityThresholding::window_size_
int window_size_
Definition: flow_velocity_thresholding.h:147
jsk_perception::FlowVelocityThresholding::~FlowVelocityThresholding
virtual ~FlowVelocityThresholding()
Definition: flow_velocity_thresholding.cpp:93
jsk_perception::FlowVelocityThresholding::use_camera_info_
bool use_camera_info_
Definition: flow_velocity_thresholding.h:142
image_encodings.h
i
int i
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
jsk_perception::FlowVelocityThresholding::unsubscribe
virtual void unsubscribe()
Definition: flow_velocity_thresholding.cpp:148
jsk_perception::FlowVelocityThresholding::image_height_
int image_height_
Definition: flow_velocity_thresholding.h:145
_1
boost::arg< 1 > _1
jsk_perception::FlowVelocityThresholding::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: flow_velocity_thresholding.h:156
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_perception::FlowVelocityThresholding::process
virtual void process(const opencv_apps::FlowArrayStamped::ConstPtr &flows_msg, const int image_height, const int image_width)
Definition: flow_velocity_thresholding.cpp:167
class_list_macros.h
jsk_perception
Definition: add_mask_image.h:48
jsk_perception::FlowVelocityThresholding::sub_info_
message_filters::Subscriber< sensor_msgs::CameraInfo > sub_info_
Definition: flow_velocity_thresholding.h:155
jsk_perception::FlowVelocityThresholding::queue_size_
int queue_size_
Definition: flow_velocity_thresholding.h:144
jsk_perception::FlowVelocityThresholding::subscribe
virtual void subscribe()
Definition: flow_velocity_thresholding.cpp:113
jsk_perception::FlowVelocityThresholding::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: flow_velocity_thresholding.h:153
_2
boost::arg< 2 > _2
message_filters::SimpleFilter::registerCallback
Connection registerCallback(const boost::function< void(P)> &callback)
jsk_perception::FlowVelocityThresholding::pub_
ros::Publisher pub_
Definition: flow_velocity_thresholding.h:151
lock
mutex_t * lock
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_perception::FlowVelocityThresholding, nodelet::Nodelet)
ROS_FATAL
#define ROS_FATAL(...)
jsk_perception::FlowVelocityThresholding::image_width_
int image_width_
Definition: flow_velocity_thresholding.h:146
jsk_perception::FlowVelocityThresholding::sub_flow_
message_filters::Subscriber< opencv_apps::FlowArrayStamped > sub_flow_
Definition: flow_velocity_thresholding.h:154
message_filters::Subscriber::subscribe
void subscribe()
f
f
nodelet::Nodelet
jsk_perception::FlowVelocityThresholding::onInit
virtual void onInit()
Definition: flow_velocity_thresholding.cpp:79
sensor_msgs::image_encodings::MONO8
const std::string MONO8
cv_bridge.h
cv_bridge::CvImage
jsk_perception::FlowVelocityThresholding
Definition: flow_velocity_thresholding.h:83
cv_utils.h
ros::V_string
std::vector< std::string > V_string
jsk_perception::FlowVelocityThresholding::mutex_
boost::mutex mutex_
Definition: flow_velocity_thresholding.h:150
jsk_perception::FlowVelocityThresholding::approximate_sync_
bool approximate_sync_
Definition: flow_velocity_thresholding.h:143
flow_velocity_thresholding.h
jsk_perception::FlowVelocityThresholding::callback
virtual void callback(const opencv_apps::FlowArrayStamped::ConstPtr &flows_msg)
Definition: flow_velocity_thresholding.cpp:154
config
config
jsk_perception::FlowVelocityThresholding::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: flow_velocity_thresholding.cpp:105
jsk_perception::FlowVelocityThresholding::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: flow_velocity_thresholding.h:152
jsk_perception::FlowVelocityThresholding::threshold_
double threshold_
Definition: flow_velocity_thresholding.h:148
info_msg
info_msg


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17