37 #include <boost/assign.hpp> 39 #include <opencv2/opencv.hpp> 48 DiagnosticNodelet::onInit();
49 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (*pnh_);
50 dynamic_reconfigure::Server<Config>::CallbackType
f =
53 srv_->setCallback (f);
55 pub_ = advertise<sensor_msgs::Image>(
73 const sensor_msgs::Image::ConstPtr& image_msg)
78 cv::Mat
label(image.size(), CV_16SC1);
80 labeling.
Exec(image.data, (
short*)
label.data, image.cols, image.rows,
83 cv::Mat label_int(image.size(), CV_32SC1);
84 for (
int j = 0; j <
label.rows; j++) {
85 for (
int i = 0; i <
label.cols; i++) {
86 label_int.at<
int>(j, i) =
label.at<
short>(j, i);
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void publish(const boost::shared_ptr< M > &message) const
int Exec(SrcT *target, DstT *result, int target_width, int target_height, const bool is_sort_region, const int region_size_min)
BlobDetectorConfig Config
PLUGINLIB_EXPORT_CLASS(jsk_perception::BlobDetector, nodelet::Nodelet)
std::vector< std::string > V_string
virtual void configCallback(Config &config, uint32_t level)
virtual void detect(const sensor_msgs::Image::ConstPtr &image_msg)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
virtual void unsubscribe()
const std::string TYPE_32SC1
sensor_msgs::ImagePtr toImageMsg() const