37 #include <boost/assign.hpp> 
   38 #include <jsk_topic_tools/log_utils.h> 
   41 #if ( CV_MAJOR_VERSION >= 4) 
   42 #include <opencv2/imgproc/imgproc_c.h> 
   49     DiagnosticNodelet::onInit();
 
   50     pub_ = advertise<sensor_msgs::Image>(*pnh_, 
"output", 1);
 
   57     sub_info_ = pnh_->subscribe(
"input/camera_info", 1,
 
   59     ros::V_string names = boost::assign::list_of(
"~input")(
"~input/camera_info");
 
   60     jsk_topic_tools::warnNoRemap(names);
 
   70     const geometry_msgs::PolygonStamped::ConstPtr& rect_msg)
 
   74       cv::Mat mask_image = cv::Mat::zeros(
camera_info_->height,
 
   77       geometry_msgs::Point32 P0 = rect_msg->polygon.points[0];
 
   78       geometry_msgs::Point32 P1 = rect_msg->polygon.points[2];
 
   79       double min_x = std::max(std::min(P0.x, P1.x), 0.0f);
 
   80       double max_x = std::max(P0.x, P1.x);
 
   81       double min_y = std::max(std::min(P0.y, P1.y), 0.0f);
 
   82       double max_y = std::max(P0.y, P1.y);
 
   85       cv::Rect region(min_x, min_y, width, height);
 
   86       cv::rectangle(mask_image, region, cv::Scalar(255), CV_FILLED);
 
   96     const sensor_msgs::CameraInfo::ConstPtr& info_msg)