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/rect_array_to_density_image.h"
00037 #include <boost/assign.hpp>
00038 #include <jsk_topic_tools/log_utils.h>
00039 #include <sensor_msgs/image_encodings.h>
00040 #include <opencv2/opencv.hpp>
00041 #include <cv_bridge/cv_bridge.h>
00042
00043 namespace jsk_perception
00044 {
00045 void RectArrayToDensityImage::onInit()
00046 {
00047 DiagnosticNodelet::onInit();
00048 pnh_->param("approximate_sync", approximate_sync_, false);
00049 pnh_->param("queue_size", queue_size_, 100);
00050 pub_ = advertise<sensor_msgs::Image>(*pnh_, "output", 1);
00051 onInitPostProcess();
00052 }
00053
00054 void RectArrayToDensityImage::subscribe()
00055 {
00056 sub_image_.subscribe(*pnh_, "input/image", 1);
00057 sub_rects_.subscribe(*pnh_, "input/rect_array", 1);
00058 if (approximate_sync_) {
00059 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(queue_size_);
00060 async_->connectInput(sub_image_, sub_rects_);
00061 async_->registerCallback(boost::bind(&RectArrayToDensityImage::convert, this, _1, _2));
00062 }
00063 else {
00064 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(queue_size_);
00065 sync_->connectInput(sub_image_, sub_rects_);
00066 sync_->registerCallback(boost::bind(&RectArrayToDensityImage::convert, this, _1, _2));
00067 }
00068 ros::V_string names = boost::assign::list_of("~input/image")("~input/rect_array");
00069 jsk_topic_tools::warnNoRemap(names);
00070 }
00071
00072 void RectArrayToDensityImage::unsubscribe()
00073 {
00074 sub_image_.unsubscribe();
00075 sub_rects_.unsubscribe();
00076 }
00077
00078 void RectArrayToDensityImage::convert(
00079 const sensor_msgs::Image::ConstPtr& image_msg,
00080 const jsk_recognition_msgs::RectArray::ConstPtr& rects_msg)
00081 {
00082 vital_checker_->poke();
00083 cv::Mat density_image = cv::Mat::zeros(image_msg->height, image_msg->width, CV_32FC1);
00084
00085
00086 for (size_t k=0; k<rects_msg->rects.size(); k++) {
00087 jsk_recognition_msgs::Rect rect = rects_msg->rects[k];
00088 for (int j=rect.y; j<(rect.y + rect.height); j++) {
00089 for (int i=rect.x; i<(rect.x + rect.width); i++) {
00090 density_image.at<float>(j, i)++;
00091 }
00092 }
00093 }
00094
00095
00096 double min_image_value;
00097 double max_image_value;
00098 cv::minMaxLoc(density_image, &min_image_value, &max_image_value);
00099 cv::Mat(density_image - min_image_value).convertTo(
00100 density_image, CV_32FC1, 1. / (max_image_value - min_image_value));
00101
00102 pub_.publish(cv_bridge::CvImage(
00103 image_msg->header,
00104 "32FC1",
00105 density_image).toImageMsg());
00106 }
00107 }
00108
00109 #include <pluginlib/class_list_macros.h>
00110 PLUGINLIB_EXPORT_CLASS (jsk_perception::RectArrayToDensityImage, nodelet::Nodelet);