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::Image>(
 
   55     sub_info_ = pnh_->subscribe(
"input/camera_info", 1,
 
   57     sub_ = pnh_->subscribe(
"input", 1,
 
   59     ros::V_string names = boost::assign::list_of(
"~input")(
"~input/camera_info");
 
   60     jsk_topic_tools::warnNoRemap(names);
 
   70     const sensor_msgs::CameraInfo::ConstPtr& info_msg)
 
   77     const jsk_recognition_msgs::PolygonArray::ConstPtr& polygon_msg)
 
   80     vital_checker_->poke();
 
   84       cv::Mat mask_image = cv::Mat::zeros(
camera_info_->height,
 
   88       int label_counter = 1;
 
   90       for (
size_t i_polygon = 0; i_polygon < polygon_msg->polygons.size(); ++i_polygon) {
 
   91         geometry_msgs::Polygon polygon = polygon_msg->polygons[i_polygon].polygon;
 
   92         std::vector<cv::Point> points;
 
   93         if (polygon.points.size() >= 3) {
 
   94           bool all_outside = 
true;
 
   95           for (
size_t i = 0; 
i < polygon.points.size(); 
i++) {
 
   96             geometry_msgs::Point32 
p = polygon.points[
i];
 
   97             cv::Point uv = 
model.project3dToPixel(cv::Point3d(
p.x, 
p.y, 
p.z));
 
  102             points.push_back(uv);
 
  105             cv::fillConvexPoly(mask_image, &(points[0]), points.size(), label_counter++);