38 #include <boost/assign.hpp>
39 #include <jsk_topic_tools/log_utils.h>
42 #include <opencv2/opencv.hpp>
48 DiagnosticNodelet::onInit();
49 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
50 dynamic_reconfigure::Server<Config>::CallbackType
f =
52 srv_->setCallback (f);
54 pub_ = advertise<sensor_msgs::Image>(*pnh_,
"output", 1);
62 jsk_topic_tools::warnNoRemap(names);
71 Config &config, uint32_t level)
80 const sensor_msgs::Image::ConstPtr& image_msg)
82 if ((image_msg->width == 0) && (image_msg->height == 0)) {
87 image_msg, image_msg->encoding);
88 cv::Mat image = cv_ptr->image;
89 cv::Mat applied_image;