37 #include <boost/assign.hpp> 39 #include <opencv2/opencv.hpp> 47 DiagnosticNodelet::onInit();
48 pub_ = advertise<sensor_msgs::Image>(*
pnh_,
"output", 1);
65 const sensor_msgs::Image::ConstPtr& mask_msg)
70 cv::Mat mask = cv_ptr->image;
73 std::vector<std::vector<cv::Point> > contours;
74 cv::findContours(mask, contours, CV_RETR_EXTERNAL, CV_CHAIN_APPROX_NONE);
76 if (contours.size() == 0) {
82 boost::tuple<int, double> max_area;
83 for (
size_t i = 0; i < contours.size(); i++) {
84 double area = cv::contourArea(contours[i]);
85 if (area > max_area.get<1>()) {
86 max_area = boost::make_tuple<int, double>(i, area);
91 std::vector<cv::Point> max_area_contour = contours[max_area.get<0>()];
92 cv::Rect rect = cv::boundingRect(cv::Mat(max_area_contour));
95 cv::Mat rect_mask = cv::Mat::zeros(mask_msg->height, mask_msg->width, CV_8UC1);
96 cv::rectangle(rect_mask, rect, cv::Scalar(255), CV_FILLED);
virtual void convert(const sensor_msgs::Image::ConstPtr &mask_msg)
void publish(const boost::shared_ptr< M > &message) const
#define NODELET_ERROR_THROTTLE(rate,...)
virtual void unsubscribe()
PLUGINLIB_EXPORT_CLASS(jsk_perception::BoundingRectMaskImage, nodelet::Nodelet)
std::vector< std::string > V_string
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
sensor_msgs::ImagePtr toImageMsg() const