37 #include <boost/assign.hpp>
38 #include <jsk_topic_tools/log_utils.h>
41 #include <opencv2/opencv.hpp>
42 #if ( CV_MAJOR_VERSION >= 4)
43 #include <opencv2/imgproc/imgproc_c.h>
51 DiagnosticNodelet::onInit();
52 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
53 dynamic_reconfigure::Server<Config>::CallbackType
f =
55 srv_->setCallback (f);
57 pub_ = advertise<sensor_msgs::Image>(*pnh_,
"output", 1);
65 jsk_topic_tools::warnNoRemap(names);
87 int max_x = std::min(min_x +
width_, (
int)
msg->width);
88 int max_y = std::min(min_y +
height_, (
int)
msg->height);
89 cv::Mat mask_image = cv::Mat::zeros(
msg->height,
msg->width, CV_8UC1);
90 cv::rectangle(mask_image,
91 cv::Point(min_x, min_y),
92 cv::Point(max_x, max_y),
93 cv::Scalar(255), CV_FILLED);