Public Types | Public Member Functions | Protected Member Functions | Protected Attributes
jsk_perception::GrabCut Class Reference

#include <grabcut.h>

Inheritance diagram for jsk_perception::GrabCut:
Inheritance graph
[legend]

List of all members.

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 ()

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_

Detailed Description

Definition at line 52 of file grabcut.h.


Member Typedef Documentation

typedef GrabCutConfig jsk_perception::GrabCut::Config

Definition at line 55 of file grabcut.h.

typedef boost::shared_ptr<GrabCut> jsk_perception::GrabCut::Ptr

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 61 of file grabcut.h.

typedef message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image> jsk_perception::GrabCut::SyncPolicy

Definition at line 59 of file grabcut.h.


Constructor & Destructor Documentation

Definition at line 62 of file grabcut.h.


Member Function Documentation

void jsk_perception::GrabCut::configCallback ( Config config,
uint32_t  level 
) [protected, virtual]

Definition at line 171 of file grabcut_nodelet.cpp.

void jsk_perception::GrabCut::onInit ( ) [protected, virtual]

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 43 of file grabcut_nodelet.cpp.

void jsk_perception::GrabCut::segment ( const sensor_msgs::Image::ConstPtr &  image_msg,
const sensor_msgs::Image::ConstPtr &  foreground_msg,
const sensor_msgs::Image::ConstPtr &  background_msg 
) [protected, virtual]

Definition at line 88 of file grabcut_nodelet.cpp.

void jsk_perception::GrabCut::subscribe ( ) [protected, virtual]

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 61 of file grabcut_nodelet.cpp.

void jsk_perception::GrabCut::unsubscribe ( ) [protected, virtual]

Implements jsk_topic_tools::ConnectionBasedNodelet.

Definition at line 72 of file grabcut_nodelet.cpp.

Reimplemented from jsk_topic_tools::DiagnosticNodelet.

Definition at line 79 of file grabcut_nodelet.cpp.


Member Data Documentation

boost::mutex jsk_perception::GrabCut::mutex_ [protected]

Definition at line 90 of file grabcut.h.

Definition at line 82 of file grabcut.h.

Definition at line 84 of file grabcut.h.

Definition at line 81 of file grabcut.h.

Definition at line 83 of file grabcut.h.

boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_perception::GrabCut::srv_ [protected]

Definition at line 89 of file grabcut.h.

Definition at line 88 of file grabcut.h.

Definition at line 87 of file grabcut.h.

Definition at line 86 of file grabcut.h.

Definition at line 85 of file grabcut.h.

Definition at line 95 of file grabcut.h.


The documentation for this class was generated from the following files:


jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Wed Sep 16 2015 04:36:16