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 <boost/assign.hpp>
00038 #include <jsk_topic_tools/log_utils.h>
00039 #include <opencv2/opencv.hpp>
00040 #include <sensor_msgs/image_encodings.h>
00041 #include <cv_bridge/cv_bridge.h>
00042
00043 namespace jsk_perception
00044 {
00045 void MaskImageToROI::onInit()
00046 {
00047 DiagnosticNodelet::onInit();
00048 pub_ = advertise<sensor_msgs::CameraInfo>(*pnh_, "output", 1);
00049 onInitPostProcess();
00050 }
00051
00052 void MaskImageToROI::subscribe()
00053 {
00054 sub_mask_ = pnh_->subscribe("input", 1, &MaskImageToROI::convert, this);
00055 sub_info_ = pnh_->subscribe("input/camera_info", 1,
00056 &MaskImageToROI::infoCallback, this);
00057 ros::V_string names = boost::assign::list_of("~input")("~input/camera_info");
00058 jsk_topic_tools::warnNoRemap(names);
00059 }
00060
00061 void MaskImageToROI::unsubscribe()
00062 {
00063 sub_mask_.shutdown();
00064 sub_info_.shutdown();
00065 }
00066
00067 void MaskImageToROI::infoCallback(
00068 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
00069 {
00070 vital_checker_->poke();
00071 boost::mutex::scoped_lock lock(mutex_);
00072 latest_camera_info_ = info_msg;
00073 }
00074
00075 void MaskImageToROI::convert(
00076 const sensor_msgs::Image::ConstPtr& mask_msg)
00077 {
00078 vital_checker_->poke();
00079 boost::mutex::scoped_lock lock(mutex_);
00080 if (latest_camera_info_) {
00081 sensor_msgs::CameraInfo camera_info(*latest_camera_info_);
00082 std::vector<cv::Point> indices;
00083 cv_bridge::CvImagePtr cv_ptr = cv_bridge::toCvCopy(
00084 mask_msg, sensor_msgs::image_encodings::MONO8);
00085 cv::Mat mask = cv_ptr->image;
00086 for (size_t j = 0; j < mask.rows; j++) {
00087 for (size_t i = 0; i < mask.cols; i++) {
00088 if (mask.at<uchar>(j, i) == 255) {
00089 indices.push_back(cv::Point(i, j));
00090 }
00091 }
00092 }
00093 cv::Rect mask_rect = cv::boundingRect(indices);
00094 camera_info.roi.x_offset = mask_rect.x;
00095 camera_info.roi.y_offset = mask_rect.y;
00096 camera_info.roi.width = mask_rect.width;
00097 camera_info.roi.height = mask_rect.height;
00098 camera_info.header = mask_msg->header;
00099 pub_.publish(camera_info);
00100 }
00101 else {
00102 NODELET_ERROR("camera info is not yet available");
00103 }
00104 }
00105
00106 }
00107
00108 #include <pluginlib/class_list_macros.h>
00109 PLUGINLIB_EXPORT_CLASS (jsk_perception::MaskImageToROI, nodelet::Nodelet);