37 #include <boost/assign.hpp> 
   38 #include <jsk_topic_tools/log_utils.h> 
   39 #include <opencv2/opencv.hpp> 
   47     DiagnosticNodelet::onInit();
 
   49     pub_ = advertise<sensor_msgs::Image>(
 
   71       async_ = boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicy> >(100);
 
   76       sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
 
   80     ros::V_string names = boost::assign::list_of(
"~input/src1")(
"~input/src2");
 
   81     jsk_topic_tools::warnNoRemap(names);
 
   91     const sensor_msgs::Image::ConstPtr& src1_msg,
 
   92     const sensor_msgs::Image::ConstPtr& src2_msg)
 
   95       src1_msg, src1_msg->encoding)->image;
 
   97       src2_msg, src2_msg->encoding)->image;
 
   99     cv::add(src1, src2, result);