37 #include <boost/assign.hpp> 40 #include <opencv2/opencv.hpp> 48 DiagnosticNodelet::onInit();
59 pub_mask_ = advertise<sensor_msgs::Image>(
60 *
pnh_,
"output/mask", 1);
62 *
pnh_,
"output/camera_info", 1);
73 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(
queue_size_);
78 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
82 ros::V_string names = boost::assign::list_of(
"~input")(
"~input/mask");
93 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
100 const sensor_msgs::Image::ConstPtr& image_msg,
101 const sensor_msgs::Image::ConstPtr& mask_msg)
107 cv::cvtColor(tmp_image, image, cv::COLOR_BGRA2BGR);
111 cv::cvtColor(tmp_image, image, cv::COLOR_RGBA2BGR);
117 if (image.cols != mask.cols || image.rows != mask.rows) {
125 cv::bitwise_not(mask, mask);
131 camera_info.header = image_msg->header;
132 camera_info.roi.x_offset = region.x;
133 camera_info.roi.y_offset = region.y;
134 camera_info.roi.width = region.width;
135 camera_info.roi.height = region.height;
141 image = image(region);
145 cv::bitwise_not(mask, mask);
153 cv::Mat masked_image = image.clone();
154 masked_image.setTo(
cval_);
155 image.copyTo(masked_image, mask);
157 cv::Mat output_image;
160 cv::cvtColor(masked_image, output_image, CV_GRAY2BGRA);
163 cv::cvtColor(masked_image, output_image, CV_RGB2BGRA);
166 cv::cvtColor(masked_image, output_image, CV_BGR2BGRA);
168 for (
size_t j=0; j < mask.rows; j++) {
169 for (
int i=0; i < mask.cols; i++) {
170 if (mask.at<uchar>(j, i) == 0) {
171 cv::Vec4b color = output_image.at<cv::Vec4b>(j, i);
173 output_image.at<cv::Vec4b>(j, i) = color;
185 cv::cvtColor(masked_image, output_image, cv::COLOR_BGR2BGRA);
188 cv::cvtColor(masked_image, output_image, cv::COLOR_BGR2RGBA);
191 masked_image.copyTo(output_image);
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
bool isRGBA(const std::string &encoding)
#define NODELET_ERROR(...)
bool isBGRA(const std::string &encoding)
void publish(const boost::shared_ptr< M > &message) const
ros::Subscriber sub_info_
ros::Publisher pub_camera_info_
bool use_rectified_image_
virtual void apply(const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::Image::ConstPtr &mask_msg)
sensor_msgs::CameraInfo::ConstPtr camera_info_
static bool isMono(const std::string &encoding)
std::vector< std::string > V_string
PLUGINLIB_EXPORT_CLASS(jsk_perception::ApplyMaskImage, nodelet::Nodelet)
boost::shared_ptr< message_filters::Synchronizer< ApproximateSyncPolicy > > async_
ros::Publisher pub_image_
bool isRGB(const std::string &encoding)
virtual void infoCallback(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
cv::Rect boundingRectOfMaskImage(const cv::Mat &image)
bool negative_before_clip_
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()
message_filters::Subscriber< sensor_msgs::Image > sub_image_
message_filters::Subscriber< sensor_msgs::Image > sub_mask_
bool mask_black_to_transparent_
sensor_msgs::ImagePtr toImageMsg() const
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_