37 #include <boost/assign.hpp> 
   38 #include <jsk_topic_tools/log_utils.h> 
   44     DiagnosticNodelet::onInit();
 
   46     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
   47     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   50     srv_->setCallback (f);
 
   52     image_pub_ = advertise<sensor_msgs::Image>(*pnh_, 
"output", 1);
 
   60 #if CV_MAJOR_VERSION >= 3 
   61     bg_ = cv::createBackgroundSubtractorMOG2();
 
   63     bg_ = cv::BackgroundSubtractorMOG2();
 
   67 #if CV_MAJOR_VERSION >= 3 
   73 #if CV_MAJOR_VERSION >= 3 
   74       bg_->setDetectShadows(1);
 
   76       bg_.set(
"detectShadows", 1);
 
   80 #if CV_MAJOR_VERSION >= 3 
   81       bg_->setDetectShadows(1);
 
   83       bg_.set(
"detectShadows", 0);
 
   93     jsk_topic_tools::warnNoRemap(names);
 
  102     const sensor_msgs::Image::ConstPtr& image_msg)
 
  104     vital_checker_->poke();
 
  108     cv::Mat image = cv_ptr->image;
 
  110     std::vector <std::vector<cv::Point > > contours;
 
  111 #if CV_MAJOR_VERSION >= 3 
  112     bg_->apply(image, fg);
 
  116     sensor_msgs::Image::Ptr diff_image