37 #include <boost/assign.hpp> 39 #if ( CV_MAJOR_VERSION >= 4) 40 #include <opencv2/imgproc/imgproc_c.h> 47 DiagnosticNodelet::onInit();
48 pub_ = advertise<sensor_msgs::Image>(
66 const sensor_msgs::CameraInfo::ConstPtr& info_msg)
68 cv::Mat mask_image = cv::Mat::zeros(info_msg->height,
71 cv::Rect rect(info_msg->roi.x_offset,
72 info_msg->roi.y_offset,
74 info_msg->roi.height);
75 cv::rectangle(mask_image, rect, cv::Scalar(255), CV_FILLED);
void publish(const boost::shared_ptr< M > &message) const
PLUGINLIB_EXPORT_CLASS(jsk_perception::ROIToMaskImage, nodelet::Nodelet)
std::vector< std::string > V_string
virtual void convert(const sensor_msgs::CameraInfo::ConstPtr &info_msg)
virtual void unsubscribe()
sensor_msgs::ImagePtr toImageMsg() const