37 #include <boost/assign.hpp> 
   38 #include <jsk_topic_tools/log_utils.h> 
   39 #include <opencv2/opencv.hpp> 
   42 #if ( CV_MAJOR_VERSION >= 4) 
   43 #include <opencv2/imgproc/imgproc_c.h> 
   50     DiagnosticNodelet::onInit();
 
   52     srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
 
   53     dynamic_reconfigure::Server<Config>::CallbackType 
f =
 
   55     srv_->setCallback (f);
 
   58     pub_ = advertise<sensor_msgs::Image>(*pnh_, 
"output", 1);
 
   65       sub_ = pnh_->subscribe(
 
   69       sub_ = pnh_->subscribe(
 
   73     jsk_topic_tools::warnNoRemap(names);
 
   88     const sensor_msgs::CameraInfo::ConstPtr& info_msg)
 
   98     const sensor_msgs::Image::ConstPtr& image_msg)
 
  101     cv::Mat 
label = cv::Mat::zeros(image_msg->height,
 
  111     for (
int v = 0; 
v < num_v; 
v++) {
 
  112       for (
int u = 0; u < num_u; u++) {
 
  115         cv::rectangle(label, region, cv::Scalar(counter), CV_FILLED);
 
  121                                     label).toImageMsg());