#include <grabcut.h>

Public Types | |
| typedef GrabCutConfig | Config |
| typedef boost::shared_ptr< GrabCut > | Ptr |
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image > | SyncPolicy |
Public Member Functions | |
| GrabCut () | |
| virtual | ~GrabCut () |
Protected Member Functions | |
| virtual void | configCallback (Config &config, uint32_t level) |
| virtual void | onInit () |
| virtual void | segment (const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::Image::ConstPtr &foreground_msg, const sensor_msgs::Image::ConstPtr &background_msg) |
| virtual void | subscribe () |
| virtual void | unsubscribe () |
| virtual void | updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Protected Attributes | |
| boost::mutex | mutex_ |
| ros::Publisher | pub_background_ |
| ros::Publisher | pub_background_mask_ |
| ros::Publisher | pub_foreground_ |
| ros::Publisher | pub_foreground_mask_ |
| boost::shared_ptr< dynamic_reconfigure::Server< Config > > | srv_ |
| message_filters::Subscriber< sensor_msgs::Image > | sub_background_ |
| message_filters::Subscriber< sensor_msgs::Image > | sub_foreground_ |
| message_filters::Subscriber< sensor_msgs::Image > | sub_image_ |
| boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > | sync_ |
| bool | use_probable_pixel_seed_ |
| typedef GrabCutConfig jsk_perception::GrabCut::Config |
| typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> jsk_perception::GrabCut::SyncPolicy |
|
virtual |
Definition at line 94 of file grabcut_nodelet.cpp.
|
protectedvirtual |
Definition at line 215 of file grabcut_nodelet.cpp.
|
protectedvirtual |
Definition at line 75 of file grabcut_nodelet.cpp.
|
protectedvirtual |
Definition at line 132 of file grabcut_nodelet.cpp.
|
protectedvirtual |
Definition at line 105 of file grabcut_nodelet.cpp.
|
protectedvirtual |
Definition at line 116 of file grabcut_nodelet.cpp.
|
protectedvirtual |
Definition at line 123 of file grabcut_nodelet.cpp.
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |
|
protected |