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/multiply_mask_image.h>
00037 #include <opencv2/opencv.hpp>
00038 #include <cv_bridge/cv_bridge.h>
00039 #include <sensor_msgs/image_encodings.h>
00040
00041 namespace jsk_perception
00042 {
00043 void MultiplyMaskImage::onInit()
00044 {
00045 DiagnosticNodelet::onInit();
00046 pnh_->param("approximate_sync", approximate_sync_, false);
00047 pub_ = advertise<sensor_msgs::Image>(
00048 *pnh_, "output", 1);
00049 }
00050
00051 void MultiplyMaskImage::subscribe()
00052 {
00053 sub_src1_.subscribe(*pnh_, "input/src1", 1);
00054 sub_src2_.subscribe(*pnh_, "input/src2", 1);
00055 if (approximate_sync_) {
00056 async_ = boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicy> >(100);
00057 async_->connectInput(sub_src1_, sub_src2_);
00058 async_->registerCallback(boost::bind(&MultiplyMaskImage::multiply, this, _1, _2));
00059 }
00060 else {
00061 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
00062 sync_->connectInput(sub_src1_, sub_src2_);
00063 sync_->registerCallback(boost::bind(&MultiplyMaskImage::multiply, this, _1, _2));
00064 }
00065 }
00066
00067 void MultiplyMaskImage::unsubscribe()
00068 {
00069 sub_src1_.unsubscribe();
00070 sub_src2_.unsubscribe();
00071 }
00072
00073 void MultiplyMaskImage::multiply(
00074 const sensor_msgs::Image::ConstPtr& src1_msg,
00075 const sensor_msgs::Image::ConstPtr& src2_msg)
00076 {
00077 cv::Mat src1 = cv_bridge::toCvShare(
00078 src1_msg, src1_msg->encoding)->image;
00079 cv::Mat src2 = cv_bridge::toCvShare(
00080 src2_msg, src2_msg->encoding)->image;
00081 cv::Mat result;
00082 cv::bitwise_and(src1, src2, result);
00083 pub_.publish(
00084 cv_bridge::CvImage(src1_msg->header,
00085 sensor_msgs::image_encodings::MONO8,
00086 result).toImageMsg());
00087 }
00088
00089 }
00090
00091
00092 #include <pluginlib/class_list_macros.h>
00093 PLUGINLIB_EXPORT_CLASS (jsk_perception::MultiplyMaskImage, nodelet::Nodelet);