apply_mask_image.cpp
Go to the documentation of this file.
1 // -*- mode: c++ -*-
2 /*********************************************************************
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2015, JSK Lab
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of the JSK Lab nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
37 #include <boost/assign.hpp>
38 #include <jsk_topic_tools/log_utils.h>
40 #include <opencv2/opencv.hpp>
41 #include <cv_bridge/cv_bridge.h>
43 
44 namespace jsk_perception
45 {
47  {
48  DiagnosticNodelet::onInit();
49  pnh_->param("approximate_sync", approximate_sync_, false);
50  pnh_->param("clip", clip_, true);
51  pnh_->param("negative", negative_, false);
52  pnh_->param("negative/before_clip", negative_before_clip_, true);
53  pnh_->param("mask_black_to_transparent", mask_black_to_transparent_, false);
54  pnh_->param("use_rectified_image", use_rectified_image_, true);
55  pnh_->param("queue_size", queue_size_, 100);
56  pnh_->param("max_interval_duration", max_interval_duration_, ros::DURATION_MAX.toSec());
57  pnh_->param("cval", cval_, 0);
58  pub_image_ = advertise<sensor_msgs::Image>(
59  *pnh_, "output", 1);
60  pub_mask_ = advertise<sensor_msgs::Image>(
61  *pnh_, "output/mask", 1);
62  pub_camera_info_ = advertise<sensor_msgs::CameraInfo>(
63  *pnh_, "output/camera_info", 1);
64  onInitPostProcess();
65  }
66 
68  // message_filters::Synchronizer needs to be called reset
69  // before message_filters::Subscriber is freed.
70  // Calling reset fixes the following error on shutdown of the nodelet:
71  // terminate called after throwing an instance of
72  // 'boost::exception_detail::clone_impl<boost::exception_detail::error_info_injector<boost::lock_error> >'
73  // what(): boost: mutex lock failed in pthread_mutex_lock: Invalid argument
74  // Also see https://github.com/ros/ros_comm/issues/720 .
75  sync_.reset();
76  async_.reset();
77  }
78 
80  {
81  sub_image_.subscribe(*pnh_, "input", 1);
82  sub_mask_.subscribe(*pnh_, "input/mask", 1);
83  sub_info_ = pnh_->subscribe("input/camera_info", 1,
85  if (approximate_sync_) {
86  async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_), (max_interval_duration_);
87  async_->connectInput(sub_image_, sub_mask_);
88  async_->registerCallback(boost::bind(&ApplyMaskImage::apply, this, _1, _2));
89  }
90  else {
91  sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
92  sync_->connectInput(sub_image_, sub_mask_);
93  sync_->registerCallback(boost::bind(&ApplyMaskImage::apply, this, _1, _2));
94  }
95  ros::V_string names = boost::assign::list_of("~input")("~input/mask");
96  jsk_topic_tools::warnNoRemap(names);
97  }
98 
100  {
103  }
104 
106  const sensor_msgs::CameraInfo::ConstPtr& info_msg)
107  {
108  boost::mutex::scoped_lock lock(mutex_);
110  }
111 
113  const sensor_msgs::Image::ConstPtr& image_msg,
114  const sensor_msgs::Image::ConstPtr& mask_msg)
115  {
116  vital_checker_->poke();
117  cv::Mat image;
118  if (jsk_recognition_utils::isBGRA(image_msg->encoding)) {
119  cv::Mat tmp_image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
120  cv::cvtColor(tmp_image, image, cv::COLOR_BGRA2BGR);
121  }
122  else if (jsk_recognition_utils::isRGBA(image_msg->encoding)) {
123  cv::Mat tmp_image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
124  cv::cvtColor(tmp_image, image, cv::COLOR_RGBA2BGR);
125  }
126  else { // BGR, RGB or GRAY
127  image = cv_bridge::toCvShare(image_msg, image_msg->encoding)->image;
128  }
129  cv::Mat mask = cv_bridge::toCvShare(mask_msg, "mono8")->image;
130  if (image.cols != mask.cols || image.rows != mask.rows) {
131  NODELET_ERROR("size of image and mask is different");
132  NODELET_ERROR("image: %dx%dx", image.cols, image.rows);
133  NODELET_ERROR("mask: %dx%dx", mask.cols, mask.rows);
134  return;
135  }
136 
138  cv::bitwise_not(mask, mask);
139  }
140 
141  cv::Rect region = jsk_recognition_utils::boundingRectOfMaskImage(mask);
142  if (camera_info_) {
143  sensor_msgs::CameraInfo camera_info(*camera_info_);
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;
149  camera_info.roi.do_rectify = use_rectified_image_;
150  pub_camera_info_.publish(camera_info);
151  }
152  if (clip_) {
153  mask = mask(region);
154  image = image(region);
155  }
156 
158  cv::bitwise_not(mask, mask);
159  }
160 
162  mask_msg->header,
163  "mono8",
164  mask).toImageMsg());
165 
166  cv::Mat masked_image = image.clone(); // should have the same dtype
167  masked_image.setTo(cval_);
168  image.copyTo(masked_image, mask);
169 
170  cv::Mat output_image;
172  // Error in cvtColor when masked_image is empty.
173  if (!masked_image.empty()) {
174  if (sensor_msgs::image_encodings::isMono(image_msg->encoding)) {
175  cv::cvtColor(masked_image, output_image, CV_GRAY2BGRA);
176  }
177  else if (jsk_recognition_utils::isRGB(image_msg->encoding)) {
178  cv::cvtColor(masked_image, output_image, CV_RGB2BGRA);
179  }
180  else { // BGR, BGRA or RGBA
181  cv::cvtColor(masked_image, output_image, CV_BGR2BGRA);
182  }
183  }
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);
188  color[3] = 0; // mask black -> transparent
189  output_image.at<cv::Vec4b>(j, i) = color;
190  }
191  }
192  }
193  // publish bgr8 image
195  image_msg->header,
197  output_image).toImageMsg());
198  }
199  else {
200  // Error in cvtColor when masked_image is empty.
201  if (!masked_image.empty()) {
202  if (jsk_recognition_utils::isBGRA(image_msg->encoding)) {
203  cv::cvtColor(masked_image, output_image, cv::COLOR_BGR2BGRA);
204  }
205  else if (jsk_recognition_utils::isRGBA(image_msg->encoding)) {
206  cv::cvtColor(masked_image, output_image, cv::COLOR_BGR2RGBA);
207  }
208  else { // BGR, RGB or GRAY
209  masked_image.copyTo(output_image);
210  }
211  }
213  image_msg->header,
214  image_msg->encoding,
215  output_image).toImageMsg());
216  }
217  }
218 }
219 
NODELET_ERROR
#define NODELET_ERROR(...)
jsk_perception::ApplyMaskImage::pub_mask_
ros::Publisher pub_mask_
Definition: apply_mask_image.h:154
jsk_recognition_utils::boundingRectOfMaskImage
cv::Rect boundingRectOfMaskImage(const cv::Mat &image)
apply_mask_image.h
image_encodings.h
jsk_perception::ApplyMaskImage::use_rectified_image_
bool use_rectified_image_
Definition: apply_mask_image.h:141
jsk_perception::ApplyMaskImage::sync_
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
Definition: apply_mask_image.h:145
i
int i
cv_bridge::CvImage::toImageMsg
sensor_msgs::ImagePtr toImageMsg() const
jsk_perception::ApplyMaskImage::negative_before_clip_
bool negative_before_clip_
Definition: apply_mask_image.h:139
_1
boost::arg< 1 > _1
jsk_perception::ApplyMaskImage::approximate_sync_
bool approximate_sync_
Definition: apply_mask_image.h:136
jsk_perception::ApplyMaskImage::async_
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
Definition: apply_mask_image.h:146
jsk_perception::ApplyMaskImage::sub_info_
ros::Subscriber sub_info_
Definition: apply_mask_image.h:152
jsk_perception::ApplyMaskImage::infoCallback
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
Definition: apply_mask_image.cpp:137
PLUGINLIB_EXPORT_CLASS
PLUGINLIB_EXPORT_CLASS(jsk_perception::ApplyMaskImage, nodelet::Nodelet)
ros::DURATION_MAX
const ROSTIME_DECL Duration DURATION_MAX
ros::Publisher::publish
void publish(const boost::shared_ptr< M > &message) const
jsk_perception::ApplyMaskImage::onInit
virtual void onInit()
Definition: apply_mask_image.cpp:78
message_filters::Subscriber::unsubscribe
void unsubscribe()
jsk_perception::ApplyMaskImage::clip_
bool clip_
Definition: apply_mask_image.h:137
jsk_recognition_utils::isBGRA
bool isBGRA(const std::string &encoding)
class_list_macros.h
jsk_perception
Definition: add_mask_image.h:48
jsk_recognition_utils::isRGB
bool isRGB(const std::string &encoding)
jsk_perception::ApplyMaskImage::pub_image_
ros::Publisher pub_image_
Definition: apply_mask_image.h:153
jsk_perception::ApplyMaskImage::negative_
bool negative_
Definition: apply_mask_image.h:138
_2
boost::arg< 2 > _2
jsk_perception::ApplyMaskImage::apply
virtual void apply(const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::Image::ConstPtr &mask_msg)
Definition: apply_mask_image.cpp:144
sensor_msgs::image_encodings::isMono
static bool isMono(const std::string &encoding)
lock
mutex_t * lock
jsk_perception::ApplyMaskImage::sub_image_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
Definition: apply_mask_image.h:149
jsk_perception::ApplyMaskImage::~ApplyMaskImage
virtual ~ApplyMaskImage()
Definition: apply_mask_image.cpp:99
message_filters::Subscriber::subscribe
void subscribe()
jsk_perception::ApplyMaskImage::subscribe
virtual void subscribe()
Definition: apply_mask_image.cpp:111
jsk_perception::ApplyMaskImage::sub_mask_
message_filters::Subscriber< sensor_msgs::Image > sub_mask_
Definition: apply_mask_image.h:150
nodelet::Nodelet
jsk_perception::ApplyMaskImage::cval_
int cval_
Definition: apply_mask_image.h:144
sensor_msgs::image_encodings::BGRA8
const std::string BGRA8
cv_bridge.h
jsk_recognition_utils::isRGBA
bool isRGBA(const std::string &encoding)
cv_bridge::CvImage
jsk_perception::ApplyMaskImage::max_interval_duration_
double max_interval_duration_
Definition: apply_mask_image.h:143
jsk_perception::ApplyMaskImage::pub_camera_info_
ros::Publisher pub_camera_info_
Definition: apply_mask_image.h:155
jsk_perception::ApplyMaskImage::mask_black_to_transparent_
bool mask_black_to_transparent_
Definition: apply_mask_image.h:140
cv_utils.h
ros::V_string
std::vector< std::string > V_string
cv_bridge::toCvShare
CvImageConstPtr toCvShare(const sensor_msgs::Image &source, const boost::shared_ptr< void const > &tracked_object, const std::string &encoding=std::string())
jsk_perception::ApplyMaskImage
Definition: apply_mask_image.h:82
jsk_perception::ApplyMaskImage::mutex_
boost::mutex mutex_
Definition: apply_mask_image.h:147
info_msg
info_msg
jsk_perception::ApplyMaskImage::unsubscribe
virtual void unsubscribe()
Definition: apply_mask_image.cpp:131
jsk_perception::ApplyMaskImage::camera_info_
sensor_msgs::CameraInfo::ConstPtr camera_info_
Definition: apply_mask_image.h:148
jsk_perception::ApplyMaskImage::queue_size_
int queue_size_
Definition: apply_mask_image.h:142


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:16