37 #include <boost/assign.hpp> 39 #include <opencv2/opencv.hpp> 47 DiagnosticNodelet::onInit();
49 pub_ = advertise<sensor_msgs::Image>(
59 async_ = boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicy> >(100);
64 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
68 ros::V_string names = boost::assign::list_of(
"~input/src1")(
"~input/src2");
79 const sensor_msgs::Image::ConstPtr& src1_msg,
80 const sensor_msgs::Image::ConstPtr& src2_msg)
83 src1_msg, src1_msg->encoding)->image;
85 src2_msg, src2_msg->encoding)->image;
87 cv::add(src1, src2, result);
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
message_filters::Subscriber< sensor_msgs::Image > sub_src1_
void publish(const boost::shared_ptr< M > &message) const
virtual void unsubscribe()
message_filters::Subscriber< sensor_msgs::Image > sub_src2_
std::vector< std::string > V_string
virtual void add(const sensor_msgs::Image::ConstPtr &src1_msg, const sensor_msgs::Image::ConstPtr &src2_msg)
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)
PLUGINLIB_EXPORT_CLASS(jsk_perception::AddMaskImage, nodelet::Nodelet)
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
sensor_msgs::ImagePtr toImageMsg() const
boost::shared_ptr< message_filters::Synchronizer< ApproxSyncPolicy > > async_