37 #include <boost/assign.hpp>
38 #include <jsk_topic_tools/log_utils.h>
39 #include <opencv2/opencv.hpp>
47 DiagnosticNodelet::onInit();
48 pub_ = advertise<sensor_msgs::CameraInfo>(*pnh_,
"output", 1);
55 sub_info_ = pnh_->subscribe(
"input/camera_info", 1,
57 ros::V_string names = boost::assign::list_of(
"~input")(
"~input/camera_info");
58 jsk_topic_tools::warnNoRemap(names);
68 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
70 vital_checker_->poke();
76 const sensor_msgs::Image::ConstPtr& mask_msg)
78 vital_checker_->poke();
82 std::vector<cv::Point> indices;
85 cv::Mat mask = cv_ptr->image;
86 for (
size_t j = 0; j < mask.rows; j++) {
87 for (
size_t i = 0;
i < mask.cols;
i++) {
88 if (mask.at<uchar>(j, i) == 255) {
89 indices.push_back(cv::Point(i, j));
93 cv::Rect mask_rect = cv::boundingRect(indices);
94 camera_info.roi.x_offset = mask_rect.x;
95 camera_info.roi.y_offset = mask_rect.y;
96 camera_info.roi.width = mask_rect.width;
97 camera_info.roi.height = mask_rect.height;
98 camera_info.header = mask_msg->header;