38 #include <boost/assign.hpp> 41 #include <opencv2/opencv.hpp> 49 DiagnosticNodelet::onInit();
50 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
51 dynamic_reconfigure::Server<Config>::CallbackType
f =
54 srv_->setCallback (f);
56 pub_ = advertise<sensor_msgs::Image>(*
pnh_,
"output", 1);
74 Config &config, uint32_t level)
83 const sensor_msgs::Image::ConstPtr& image_msg)
89 type = cv::MORPH_RECT;
92 type = cv::MORPH_CROSS;
95 type = cv::MORPH_ELLIPSE;
99 cv::Mat element = cv::getStructuringElement(
103 apply(image, output_image, element);
111 const cv::Mat& input, cv::Mat& output,
const cv::Mat& element)
113 cv::morphologyEx(input, output, operation_, element,
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void publish(const boost::shared_ptr< M > &message) const
virtual void imageCallback(const sensor_msgs::Image::ConstPtr &image_msg)
virtual void apply(const cv::Mat &input, cv::Mat &output, const cv::Mat &element)=0
virtual void unsubscribe()
jsk_perception::MorphologicalMaskImageOperatorConfig Config
std::vector< std::string > V_string
PLUGINLIB_EXPORT_CLASS(jsk_perception::Dilate, nodelet::Nodelet)
virtual void apply(const cv::Mat &input, cv::Mat &output, const cv::Mat &element)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
sensor_msgs::ImagePtr toImageMsg() const
virtual void configCallback(Config &config, uint32_t level)