37 #include <boost/assign.hpp>
38 #include <jsk_topic_tools/log_utils.h>
40 #include <opencv2/opencv.hpp>
48 DiagnosticNodelet::onInit();
50 pnh_->param(
"clip",
clip_,
true);
51 pnh_->param(
"negative",
negative_,
false);
57 pnh_->param(
"cval",
cval_, 0);
60 pub_mask_ = advertise<sensor_msgs::Image>(
61 *pnh_,
"output/mask", 1);
63 *pnh_,
"output/camera_info", 1);
83 sub_info_ = pnh_->subscribe(
"input/camera_info", 1,
91 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
95 ros::V_string names = boost::assign::list_of(
"~input")(
"~input/mask");
96 jsk_topic_tools::warnNoRemap(names);
106 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
113 const sensor_msgs::Image::ConstPtr& image_msg,
114 const sensor_msgs::Image::ConstPtr& mask_msg)
116 vital_checker_->poke();
120 cv::cvtColor(tmp_image, image, cv::COLOR_BGRA2BGR);
124 cv::cvtColor(tmp_image, image, cv::COLOR_RGBA2BGR);
130 if (image.cols != mask.cols || image.rows != mask.rows) {
138 cv::bitwise_not(mask, mask);
144 camera_info.header = image_msg->header;
145 camera_info.roi.x_offset = region.x;
146 camera_info.roi.y_offset = region.y;
147 camera_info.roi.width = region.width;
148 camera_info.roi.height = region.height;
154 image = image(region);
158 cv::bitwise_not(mask, mask);
166 cv::Mat masked_image = image.clone();
167 masked_image.setTo(
cval_);
168 image.copyTo(masked_image, mask);
170 cv::Mat output_image;
173 if (!masked_image.empty()) {
175 cv::cvtColor(masked_image, output_image, CV_GRAY2BGRA);
178 cv::cvtColor(masked_image, output_image, CV_RGB2BGRA);
181 cv::cvtColor(masked_image, output_image, CV_BGR2BGRA);
184 for (
size_t j=0; j < mask.rows; j++) {
185 for (
int i=0;
i < mask.cols;
i++) {
186 if (mask.at<uchar>(j, i) == 0) {
187 cv::Vec4b color = output_image.at<cv::Vec4b>(j,
i);
189 output_image.at<cv::Vec4b>(j,
i) = color;
201 if (!masked_image.empty()) {
203 cv::cvtColor(masked_image, output_image, cv::COLOR_BGR2BGRA);
206 cv::cvtColor(masked_image, output_image, cv::COLOR_BGR2RGBA);
209 masked_image.copyTo(output_image);