37 #include <boost/assign.hpp>
38 #include <jsk_topic_tools/log_utils.h>
40 #include <opencv2/opencv.hpp>
47 DiagnosticNodelet::onInit();
50 pub_ = advertise<sensor_msgs::Image>(*pnh_,
"output", 1);
71 async_ = boost::make_shared<message_filters::Synchronizer<ApproximateSyncPolicy> >(
queue_size_);
76 sync_ = boost::make_shared<message_filters::Synchronizer<SyncPolicy> >(
queue_size_);
80 ros::V_string names = boost::assign::list_of(
"~input/image")(
"~input/rect_array");
81 jsk_topic_tools::warnNoRemap(names);
91 const sensor_msgs::Image::ConstPtr& image_msg,
92 const jsk_recognition_msgs::RectArray::ConstPtr& rects_msg)
94 vital_checker_->poke();
95 cv::Mat density_image = cv::Mat::zeros(image_msg->height, image_msg->width, CV_32FC1);
98 for (
size_t k=0;
k<rects_msg->rects.size();
k++) {
99 jsk_recognition_msgs::Rect rect = rects_msg->rects[
k];
100 for (
int j=rect.y; j<(rect.y + rect.height); j++) {
101 for (
int i=rect.x;
i<(rect.x + rect.width);
i++) {
102 density_image.at<
float>(j,
i)++;
108 double min_image_value;
109 double max_image_value;
110 cv::minMaxLoc(density_image, &min_image_value, &max_image_value);
111 cv::Mat(density_image - min_image_value).convertTo(
112 density_image, CV_32FC1, 1. / (max_image_value - min_image_value));