37 #include <boost/assign.hpp>
38 #include <jsk_topic_tools/log_utils.h>
39 #include <opencv2/opencv.hpp>
47 DiagnosticNodelet::onInit();
50 pub_ = advertise<sensor_msgs::Image>(
72 async_ = boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicy> >(
queue_size_);
81 ros::V_string names = boost::assign::list_of(
"~input/src1")(
"~input/src2");
82 jsk_topic_tools::warnNoRemap(names);
92 const sensor_msgs::Image::ConstPtr& src1_msg,
93 const sensor_msgs::Image::ConstPtr& src2_msg)
96 src1_msg, src1_msg->encoding)->image;
98 src2_msg, src2_msg->encoding)->image;
100 cv::bitwise_and(src1, src2, result);