37 #include <boost/assign.hpp> 39 #include <opencv2/opencv.hpp> 47 DiagnosticNodelet::onInit();
50 pub_ = advertise<sensor_msgs::Image>(
60 async_ = boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicy> >(
queue_size_);
65 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
69 ros::V_string names = boost::assign::list_of(
"~input/src1")(
"~input/src2");
80 const sensor_msgs::Image::ConstPtr& src1_msg,
81 const sensor_msgs::Image::ConstPtr& src2_msg)
84 src1_msg, src1_msg->encoding)->image;
86 src2_msg, src2_msg->encoding)->image;
88 cv::bitwise_and(src1, src2, result);
virtual void unsubscribe()
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
virtual void multiply(const sensor_msgs::Image::ConstPtr &src1_msg, const sensor_msgs::Image::ConstPtr &src2_msg)
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
PLUGINLIB_EXPORT_CLASS(jsk_perception::MultiplyMaskImage, nodelet::Nodelet)
std::vector< std::string > V_string
message_filters::Subscriber< sensor_msgs::Image > sub_src2_
void subscribe(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=0)
boost::shared_ptr< message_filters::Synchronizer< ApproxSyncPolicy > > async_
message_filters::Subscriber< sensor_msgs::Image > sub_src1_
sensor_msgs::ImagePtr toImageMsg() const