41 #include <boost/assign.hpp> 42 #include <opencv2/opencv.hpp> 52 DiagnosticNodelet::onInit();
55 pub_ = advertise<sensor_msgs::Image>(
65 async_ = boost::make_shared<message_filters::Synchronizer<ApproxSyncPolicy> >(
queue_size_);
70 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
83 const sensor_msgs::Image::ConstPtr& src1_msg,
84 const sensor_msgs::Image::ConstPtr& src2_msg)
88 if (src1_msg->width != src2_msg->width || src1_msg->height != src2_msg->height)
91 NODELET_ERROR(
"input/src1 = %dx%d", src1_msg->width, src1_msg->height);
92 NODELET_ERROR(
"input/src2 = %dx%d", src2_msg->width, src2_msg->height);
100 cv::bitwise_not(mask2, mask2_not);
102 cv::Mat
result = cv::Mat::zeros(mask1.size(), mask1.type());
103 mask1.copyTo(result, mask2_not);
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
#define NODELET_ERROR(...)
void publish(const boost::shared_ptr< M > &message) const
message_filters::Subscriber< sensor_msgs::Image > sub_src1_
PLUGINLIB_EXPORT_CLASS(jsk_perception::SubtractMaskImage, nodelet::Nodelet)
message_filters::Subscriber< sensor_msgs::Image > sub_src2_
virtual void subtract(const sensor_msgs::Image::ConstPtr &src1_msg, const sensor_msgs::Image::ConstPtr &src2_msg)
virtual void unsubscribe()
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< SyncPolicy > > sync_
boost::shared_ptr< message_filters::Synchronizer< ApproxSyncPolicy > > async_
sensor_msgs::ImagePtr toImageMsg() const