video_to_scene.cpp
Go to the documentation of this file.
1 // -*- mode: C++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2022, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 /*
36  * video_to_scene.cpp
37  * Author: Kei Okada <k-okada@jsk.t.u-tokyo.ac.jp>
38  */
39 
41 #include <boost/assign.hpp>
42 
43 namespace jsk_perception{
44  void VideoToScene::onInit(){
45  DiagnosticNodelet::onInit();
46 
47  bgsubtractor = cv::bgsegm::createBackgroundSubtractorGMG();
48  pnh_->param("min_percent", min_percent_, 5);
49  pnh_->param("max_percent", max_percent_, 20);
50  captured_ = false;
51 
52  srv_ = boost::make_shared<dynamic_reconfigure::Server<Config> > (*pnh_);
53  dynamic_reconfigure::Server<Config>::CallbackType f =
54  boost::bind(&VideoToScene::configCallback, this, _1, _2);
55  srv_->setCallback (f);
56 
57  //pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
58  pub_ = advertiseImage(*pnh_, "output", 1);
59 
60  onInitPostProcess();
61  }
62 
64  std::string transport;
65  pnh_->param("image_transport", transport, std::string("raw"));
66  NODELET_INFO_STREAM("Using transport \"" << transport << "\"");
67  image_transport::TransportHints hints(transport, ros::TransportHints(), *pnh_);
68  //
69  it_.reset(new image_transport::ImageTransport(*pnh_));
70  sub_ = it_->subscribe(pnh_->resolveName("input"), 1, &VideoToScene::work, this, hints);
71  ros::V_string names = boost::assign::list_of("input");
72  jsk_topic_tools::warnNoRemap(names);
73  }
74 
77  }
78 
79  void VideoToScene::work(const sensor_msgs::Image::ConstPtr& image_msg){
80  cv::Mat image;
81 
82  vital_checker_ -> poke();
83  boost::mutex::scoped_lock lock(mutex_);
84 
85  image = cv_bridge::toCvShare(image_msg, sensor_msgs::image_encodings::RGB8) -> image;
86  cv::resize(image, image, cv::Size(), 300.0/image.cols, 300.0/image.cols);
87 
88  cv::Mat bgmask;
89  bgsubtractor->apply(image, bgmask);
90  cv::erode(bgmask, bgmask, cv::Mat(), cv::Point(-1, -1), 2);
91  cv::dilate(bgmask, bgmask, cv::Mat(), cv::Point(-1, -1), 2);
92 
93  int p = cv::countNonZero(bgmask) / float(bgmask.cols * bgmask.rows) * 100;
94  NODELET_DEBUG_STREAM("p = " << p << ", min_percent = " << min_percent_ << ", max_percent = " << max_percent_ << ", captured = " << captured_);
95 
96  if ( p < min_percent_ && !captured_ ) {
97  captured_ = true;
98  pub_.publish(image_msg);
99  } else if ( captured_ && p >= max_percent_ ) {
100  captured_ = false;
101  }
102  }
103 
104  void VideoToScene::configCallback(Config &config, uint32_t level){
105  boost::mutex::scoped_lock lock(mutex_);
106  min_percent_ = config.min_percent;
107  max_percent_ = config.max_percent;
108  }
109 }
110 
jsk_perception::VideoToScene::configCallback
virtual void configCallback(Config &config, uint32_t level)
Definition: video_to_scene.cpp:136
ssd_train_dataset.float
float
Definition: ssd_train_dataset.py:180
image_transport::ImageTransport
jsk_perception::VideoToScene::min_percent_
int min_percent_
Definition: video_to_scene.h:138
jsk_perception::VideoToScene::it_
boost::shared_ptr< image_transport::ImageTransport > it_
Definition: video_to_scene.h:133
jsk_perception::VideoToScene::work
virtual void work(const sensor_msgs::Image::ConstPtr &image_msg)
Definition: video_to_scene.cpp:111
ros::TransportHints
jsk_perception::VideoToScene::pub_
image_transport::Publisher pub_
Definition: video_to_scene.h:134
sensor_msgs::image_encodings::RGB8
const std::string RGB8
video_to_scene.h
jsk_perception::VideoToScene::sub_
image_transport::Subscriber sub_
Definition: video_to_scene.h:132
jsk_perception::VideoToScene::srv_
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
Definition: video_to_scene.h:131
jsk_perception::VideoToScene::unsubscribe
virtual void unsubscribe()
Definition: video_to_scene.cpp:107
jsk_perception::VideoToScene::mutex_
boost::mutex mutex_
Definition: video_to_scene.h:135
class_list_macros.h
jsk_perception
Definition: add_mask_image.h:48
jsk_perception::VideoToScene::onInit
virtual void onInit()
Definition: video_to_scene.cpp:76
jsk_perception::VideoToScene::bgsubtractor
cv::Ptr< cv::bgsegm::BackgroundSubtractorGMG > bgsubtractor
Definition: video_to_scene.h:137
jsk_perception::VideoToScene::captured_
bool captured_
Definition: video_to_scene.h:140
node_scripts.pointit.p
p
Definition: pointit.py:231
lock
mutex_t * lock
image_transport::Publisher::publish
void publish(const sensor_msgs::Image &message) const
jsk_perception::VideoToScene
Definition: video_to_scene.h:88
f
f
nodelet::Nodelet
jsk_perception::VideoToScene::max_percent_
int max_percent_
Definition: video_to_scene.h:139
NODELET_DEBUG_STREAM
#define NODELET_DEBUG_STREAM(...)
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_perception::VideoToScene, nodelet::Nodelet)
ros::V_string
std::vector< std::string > V_string
image_transport::TransportHints
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
NODELET_INFO_STREAM
#define NODELET_INFO_STREAM(...)
jsk_perception::VideoToScene::subscribe
virtual void subscribe()
Definition: video_to_scene.cpp:95
config
config
image_transport::Subscriber::shutdown
void shutdown()


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