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 geometry_msgs::PolygonStamped::ConstPtr& polygon_msg)
 
   80     vital_checker_->poke();
 
   82       if (polygon_msg->header.frame_id != 
camera_info_->header.frame_id) {
 
   83         NODELET_ERROR(
"frame_id of polygon (%s) and camera (%s) are not same.",
 
   84                       polygon_msg->header.frame_id.c_str(), 
camera_info_->header.frame_id.c_str());
 
   89       cv::Mat mask_image = cv::Mat::zeros(
camera_info_->height,
 
   92       std::vector<cv::Point> points;
 
   94       if (polygon_msg->polygon.points.size() >= 3) {
 
   95         for (
size_t i = 0; 
i < polygon_msg->polygon.points.size(); 
i++) {
 
   96           geometry_msgs::Point32 
p = polygon_msg->polygon.points[
i];
 
   97           cv::Point uv = 
model.project3dToPixel(cv::Point3d(
p.x, 
p.y, 
p.z));
 
  100         cv::fillConvexPoly(mask_image, &(points[0]), points.size(), cv::Scalar(255));