38 #include <boost/assign.hpp> 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);
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;
virtual void apply(const sensor_msgs::Image::ConstPtr &image_msg)
void publish(const boost::shared_ptr< M > &message) const
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
std::vector< std::string > V_string
PLUGINLIB_EXPORT_CLASS(jsk_perception::GaussianBlur, nodelet::Nodelet)
CvImagePtr toCvCopy(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
jsk_perception::GaussianBlurConfig Config
virtual void configCallback(Config &config, uint32_t level)
virtual void unsubscribe()
sensor_msgs::ImagePtr toImageMsg() const