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
00037
00038
00039
00040 #include <jsk_perception/subtract_mask_image.h>
00041 #include <boost/assign.hpp>
00042 #include <opencv2/opencv.hpp>
00043 #include <cv_bridge/cv_bridge.h>
00044 #include <sensor_msgs/image_encodings.h>
00045
00046 namespace enc = sensor_msgs::image_encodings;
00047
00048 namespace jsk_perception
00049 {
00050 void SubtractMaskImage::onInit()
00051 {
00052 DiagnosticNodelet::onInit();
00053 pnh_->param("approximate_sync", approximate_sync_, false);
00054 pnh_->param("queue_size", queue_size_, 100);
00055 pub_ = advertise<sensor_msgs::Image>(
00056 *pnh_, "output", 1);
00057 onInitPostProcess();
00058 }
00059
00060 void SubtractMaskImage::subscribe()
00061 {
00062 sub_src1_.subscribe(*pnh_, "input/src1", 1);
00063 sub_src2_.subscribe(*pnh_, "input/src2", 1);
00064 if (approximate_sync_) {
00065 async_ = boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicy> >(queue_size_);
00066 async_->connectInput(sub_src1_, sub_src2_);
00067 async_->registerCallback(boost::bind(&SubtractMaskImage::subtract, this, _1, _2));
00068 }
00069 else {
00070 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
00071 sync_->connectInput(sub_src1_, sub_src2_);
00072 sync_->registerCallback(boost::bind(&SubtractMaskImage::subtract, this, _1, _2));
00073 }
00074 }
00075
00076 void SubtractMaskImage::unsubscribe()
00077 {
00078 sub_src1_.unsubscribe();
00079 sub_src2_.unsubscribe();
00080 }
00081
00082 void SubtractMaskImage::subtract(
00083 const sensor_msgs::Image::ConstPtr& src1_msg,
00084 const sensor_msgs::Image::ConstPtr& src2_msg)
00085 {
00086 vital_checker_->poke();
00087
00088 if (src1_msg->width != src2_msg->width || src1_msg->height != src2_msg->height)
00089 {
00090 NODELET_ERROR("Size of masks are different!");
00091 NODELET_ERROR("input/src1 = %dx%d", src1_msg->width, src1_msg->height);
00092 NODELET_ERROR("input/src2 = %dx%d", src2_msg->width, src2_msg->height);
00093 return;
00094 }
00095
00096 cv::Mat mask1 = cv_bridge::toCvShare(src1_msg, enc::MONO8)->image;
00097 cv::Mat mask2 = cv_bridge::toCvShare(src2_msg, enc::MONO8)->image;
00098
00099 cv::Mat mask2_not;
00100 cv::bitwise_not(mask2, mask2_not);
00101
00102 cv::Mat result = cv::Mat::zeros(mask1.size(), mask1.type());
00103 mask1.copyTo(result, mask2_not);
00104 pub_.publish(
00105 cv_bridge::CvImage(src1_msg->header, enc::MONO8, result).toImageMsg());
00106 }
00107 }
00108
00109 #include <pluginlib/class_list_macros.h>
00110 PLUGINLIB_EXPORT_CLASS (jsk_perception::SubtractMaskImage, nodelet::Nodelet);