37 #include <boost/assign.hpp>
38 #include <jsk_topic_tools/log_utils.h>
40 #include <opencv2/opencv.hpp>
48 DiagnosticNodelet::onInit();
72 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(100);
77 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(100);
81 ros::V_string names = boost::assign::list_of(
"~input")(
"~input/mask");
82 jsk_topic_tools::warnNoRemap(names);
92 const sensor_msgs::Image::ConstPtr& image_msg,
93 const sensor_msgs::Image::ConstPtr& mask_msg)
95 vital_checker_->poke();
97 image_msg->encoding)->image;
99 mask_msg->encoding)->image;
101 bool single_channel =
false;
104 single_channel =
false;
107 single_channel =
true;
109 if (single_channel) {
110 output = cv::Mat::zeros(mask.rows, mask.cols, CV_8UC1);
113 output = cv::Mat::zeros(mask.rows, mask.cols, CV_8UC3);
117 for (
int j = 0; j < image.rows; j++) {
118 for (
int i = 0;
i < image.cols;
i++) {
119 if (single_channel) {
120 output.at<uchar>(j + region.y,
i + region.x)
121 = image.at<uchar>(j,
i);
124 output.at<cv::Vec3b>(j + region.y,
i + region.x)
125 = image.at<cv::Vec3b>(j,
i);