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