Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036 #include "jsk_perception/mask_image_to_roi.h"
00037 #include <opencv2/opencv.hpp>
00038 #include <sensor_msgs/image_encodings.h>
00039 #include <cv_bridge/cv_bridge.h>
00040
00041 namespace jsk_perception
00042 {
00043 void MaskImageToROI::onInit()
00044 {
00045 DiagnosticNodelet::onInit();
00046 pub_ = advertise<sensor_msgs::CameraInfo>(*pnh_, "output", 1);
00047 }
00048
00049 void MaskImageToROI::subscribe()
00050 {
00051 sub_mask_ = pnh_->subscribe("input", 1, &MaskImageToROI::convert, this);
00052 sub_info_ = pnh_->subscribe("input/camera_info", 1,
00053 &MaskImageToROI::infoCallback, this);
00054 }
00055
00056 void MaskImageToROI::unsubscribe()
00057 {
00058 sub_mask_.shutdown();
00059 sub_info_.shutdown();
00060 }
00061
00062 void MaskImageToROI::infoCallback(
00063 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00064 {
00065 vital_checker_->poke();
00066 boost::mutex::scoped_lock lock(mutex_);
00067 latest_camera_info_ = info_msg;
00068 }
00069
00070 void MaskImageToROI::convert(
00071 const sensor_msgs::Image::ConstPtr& mask_msg)
00072 {
00073 vital_checker_->poke();
00074 boost::mutex::scoped_lock lock(mutex_);
00075 if (latest_camera_info_) {
00076 sensor_msgs::CameraInfo camera_info(*latest_camera_info_);
00077 std::vector<cv::Point> indices;
00078 cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00079 mask_msg, sensor_msgs::image_encodings::MONO8);
00080 cv::Mat mask = cv_ptr->image;
00081 for (size_t j = 0; j < mask.rows; j++) {
00082 for (size_t i = 0; i < mask.cols; i++) {
00083 if (mask.at<uchar>(j, i) == 255) {
00084 indices.push_back(cv::Point(i, j));
00085 }
00086 }
00087 }
00088 cv::Rect mask_rect = cv::boundingRect(indices);
00089 camera_info.roi.x_offset = mask_rect.x;
00090 camera_info.roi.y_offset = mask_rect.y;
00091 camera_info.roi.width = mask_rect.width;
00092 camera_info.roi.height = mask_rect.height;
00093 camera_info.header = mask_msg->header;
00094 pub_.publish(camera_info);
00095 }
00096 else {
00097 JSK_NODELET_ERROR("camera info is not yet available");
00098 }
00099 }
00100
00101 }
00102
00103 #include <pluginlib/class_list_macros.h>
00104 PLUGINLIB_EXPORT_CLASS (jsk_perception::MaskImageToROI, nodelet::Nodelet);