38 #include <boost/assign.hpp> 47 ROS_WARN(
"Maybe this node does not work for large size images with segfault.");
50 srv_ = boost::make_shared <dynamic_reconfigure::Server<Config> > (
pnh_);
51 dynamic_reconfigure::Server<Config>::CallbackType
f =
54 srv_->setCallback (f);
76 if (in_image.channels() == 1) {
78 cv::cvtColor(in_image, bgr_image, CV_GRAY2BGR);
82 cv::cvtColor(in_image, bgr_image, CV_RGB2BGR);
88 cv::Mat lab_image, out_image, mean_color_image, center_grid_image;
91 bgr_image.copyTo(out_image);
92 bgr_image.copyTo(mean_color_image);
93 bgr_image.copyTo(center_grid_image);
95 cv::cvtColor(bgr_image, lab_image, CV_BGR2Lab);
96 int w = image->width,
h = image->height;
125 cv::transpose(slic.
clusters, clusters);
126 clusters = clusters + cv::Scalar(1);
CvImageConstPtr toCvShare(const sensor_msgs::ImageConstPtr &source, const std::string &encoding=std::string())
void create_connectivity(const cv::Mat &image)
void publish(const boost::shared_ptr< M > &message) const
virtual void imageCallback(const sensor_msgs::Image::ConstPtr &image)
PLUGINLIB_EXPORT_CLASS(jsk_perception::SLICSuperPixels, nodelet::Nodelet)
boost::shared_ptr< image_transport::ImageTransport > it_
image_transport::Subscriber image_sub_
ros::NodeHandle & getPrivateNodeHandle() const
std::vector< std::string > V_string
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
SLICSuperPixelsConfig Config
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int number_of_super_pixels_
ros::NodeHandle & getNodeHandle() const
ros::Publisher pub_debug_mean_color_
void generate_superpixels(const cv::Mat &image, int step, int nc)
virtual void configCallback(Config &config, uint32_t level)
ros::Publisher pub_debug_
ros::Publisher pub_debug_center_grid_
void display_contours(cv::Mat &image, cv::Vec3b colour)
void colour_with_cluster_means(cv::Mat &image)
void display_center_grid(cv::Mat &image, cv::Scalar colour)
const std::string TYPE_32SC1
sensor_msgs::ImagePtr toImageMsg() const
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_