Go to the documentation of this file.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
00036 #include "jsk_perception/background_substraction.h"
00037 #include <boost/assign.hpp>
00038 #include <jsk_topic_tools/log_utils.h>
00039
00040 namespace jsk_perception
00041 {
00042 void BackgroundSubstraction::onInit()
00043 {
00044 DiagnosticNodelet::onInit();
00045
00046 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
00047 dynamic_reconfigure::Server<Config>::CallbackType f =
00048 boost::bind (
00049 &BackgroundSubstraction::configCallback, this, _1, _2);
00050 srv_->setCallback (f);
00051
00052 image_pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00053
00054 onInitPostProcess();
00055 }
00056
00057 void BackgroundSubstraction::configCallback(Config& config, uint32_t level)
00058 {
00059 boost::mutex::scoped_lock lock(mutex_);
00060 #if CV_MAJOR_VERSION >= 3
00061 bg_ = cv::createBackgroundSubtractorMOG2();
00062 #else
00063 bg_ = cv::BackgroundSubtractorMOG2();
00064 #endif
00065 nmixtures_ = config.nmixtures;
00066 detect_shadows_ = config.detect_shadows;
00067 #if CV_MAJOR_VERSION >= 3
00068 bg_->setNMixtures(nmixtures_);
00069 #else
00070 bg_.set("nmixtures", nmixtures_);
00071 #endif
00072 if (detect_shadows_) {
00073 #if CV_MAJOR_VERSION >= 3
00074 bg_->setDetectShadows(1);
00075 #else
00076 bg_.set("detectShadows", 1);
00077 #endif
00078 }
00079 else {
00080 #if CV_MAJOR_VERSION >= 3
00081 bg_->setDetectShadows(1);
00082 #else
00083 bg_.set("detectShadows", 0);
00084 #endif
00085 }
00086 }
00087
00088 void BackgroundSubstraction::subscribe()
00089 {
00090 it_.reset(new image_transport::ImageTransport(*pnh_));
00091 sub_ = it_->subscribe("image", 1, &BackgroundSubstraction::substract, this);
00092 ros::V_string names = boost::assign::list_of("image");
00093 jsk_topic_tools::warnNoRemap(names);
00094 }
00095
00096 void BackgroundSubstraction::unsubscribe()
00097 {
00098 sub_.shutdown();
00099 }
00100
00101 void BackgroundSubstraction::substract(
00102 const sensor_msgs::Image::ConstPtr& image_msg)
00103 {
00104 vital_checker_->poke();
00105 boost::mutex::scoped_lock lock(mutex_);
00106 cv_bridge::CvImagePtr cv_ptr
00107 = cv_bridge::toCvCopy(image_msg, sensor_msgs::image_encodings::BGR8);
00108 cv::Mat image = cv_ptr->image;
00109 cv::Mat fg;
00110 std::vector <std::vector<cv::Point > > contours;
00111 #if CV_MAJOR_VERSION >= 3
00112 bg_->apply(image, fg);
00113 #else
00114 bg_(image, fg);
00115 #endif
00116 sensor_msgs::Image::Ptr diff_image
00117 = cv_bridge::CvImage(image_msg->header,
00118 sensor_msgs::image_encodings::MONO8,
00119 fg).toImageMsg();
00120 image_pub_.publish(diff_image);
00121 }
00122 }
00123
00124 #include <pluginlib/class_list_macros.h>
00125 PLUGINLIB_EXPORT_CLASS (jsk_perception::BackgroundSubstraction, nodelet::Nodelet);