37 #include <boost/assign.hpp> 40 #include <opencv2/opencv.hpp> 48 DiagnosticNodelet::onInit();
60 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
65 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
69 ros::V_string names = boost::assign::list_of(
"~input")(
"~input/mask");
80 const sensor_msgs::Image::ConstPtr& image_msg,
81 const sensor_msgs::Image::ConstPtr& mask_msg)
85 image_msg->encoding)->image;
87 mask_msg->encoding)->image;
89 bool single_channel =
false;
92 single_channel =
false;
95 single_channel =
true;
98 output = cv::Mat::zeros(mask.rows, mask.cols, CV_8UC1);
101 output = cv::Mat::zeros(mask.rows, mask.cols, CV_8UC3);
105 for (
int j = 0; j < image.rows; j++) {
106 for (
int i = 0; i < image.cols; i++) {
107 if (single_channel) {
108 output.at<uchar>(j + region.y, i + region.x)
109 = image.at<uchar>(j, i);
112 output.at<cv::Vec3b>(j + region.y, i + region.x)
113 = image.at<cv::Vec3b>(j, i);
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
std::vector< std::string > V_string
void output(int index, double value)
ros::Publisher pub_image_
PLUGINLIB_EXPORT_CLASS(jsk_perception::UnapplyMaskImage, nodelet::Nodelet)
cv::Rect boundingRectOfMaskImage(const cv::Mat &image)
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)
virtual void unsubscribe()
virtual void apply(const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::Image::ConstPtr &mask_msg)
message_filters::Subscriber< sensor_msgs::Image > sub_mask_
sensor_msgs::ImagePtr toImageMsg() const