Public Member Functions | |
| void | imageCallback (const sensor_msgs::ImageConstPtr &msg_ptr) |
| cv::Mat | smoothClutter (cv::Mat &sp_img, cv::Mat &label_img, int num_regions) |
| bool | smoothClutterService (SmoothClutter::Request &req, SmoothClutter::Response &res) |
| void | spin () |
| SuperpixelSmootherNode (ros::NodeHandle n) | |
Protected Attributes | |
| sensor_msgs::CvBridge | bridge_ |
| image_transport::Subscriber | image_sub_ |
| image_transport::ImageTransport | it_ |
| double | k_ |
| image_transport::Publisher | label_pub_ |
| int | min_size_ |
| ros::NodeHandle | n_ |
| double | sigma_ |
| ros::ServiceServer | smoother_srv_ |
Definition at line 15 of file superpixel_smoother_node.cpp.
Definition at line 18 of file superpixel_smoother_node.cpp.
| void SuperpixelSmootherNode::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg_ptr | ) | [inline] |
Method to take an image comping in on the image_sub_ topic and publishes the superpixel label version of the image over the topic label_pub_
| msg_ptr | Input from the image_sub_ subscriber |
Definition at line 153 of file superpixel_smoother_node.cpp.
| cv::Mat SuperpixelSmootherNode::smoothClutter | ( | cv::Mat & | sp_img, |
| cv::Mat & | label_img, | ||
| int | num_regions | ||
| ) | [inline] |
Definition at line 37 of file superpixel_smoother_node.cpp.
| bool SuperpixelSmootherNode::smoothClutterService | ( | SmoothClutter::Request & | req, |
| SmoothClutter::Response & | res | ||
| ) | [inline] |
Definition at line 123 of file superpixel_smoother_node.cpp.
| void SuperpixelSmootherNode::spin | ( | ) | [inline] |
Simple method to keep the node running.
Definition at line 173 of file superpixel_smoother_node.cpp.
sensor_msgs::CvBridge SuperpixelSmootherNode::bridge_ [protected] |
Definition at line 187 of file superpixel_smoother_node.cpp.
Definition at line 185 of file superpixel_smoother_node.cpp.
Definition at line 184 of file superpixel_smoother_node.cpp.
double SuperpixelSmootherNode::k_ [protected] |
Definition at line 189 of file superpixel_smoother_node.cpp.
Definition at line 186 of file superpixel_smoother_node.cpp.
int SuperpixelSmootherNode::min_size_ [protected] |
Definition at line 190 of file superpixel_smoother_node.cpp.
ros::NodeHandle SuperpixelSmootherNode::n_ [protected] |
Definition at line 182 of file superpixel_smoother_node.cpp.
double SuperpixelSmootherNode::sigma_ [protected] |
Definition at line 188 of file superpixel_smoother_node.cpp.
Definition at line 183 of file superpixel_smoother_node.cpp.