Go to the documentation of this file.
37 #ifndef JSK_PERCEPTION_GRABCUT_H_
38 #define JSK_PERCEPTION_GRABCUT_H_
40 #include <sensor_msgs/Image.h>
46 #include <jsk_topic_tools/diagnostic_nodelet.h>
47 #include <dynamic_reconfigure/server.h>
48 #include "jsk_perception/GrabCutConfig.h"
52 class GrabCut:
public jsk_topic_tools::DiagnosticNodelet
55 typedef GrabCutConfig
Config;
62 GrabCut() : DiagnosticNodelet(
"GrabCut") {}
75 const sensor_msgs::Image::ConstPtr& image_msg,
76 const sensor_msgs::Image::ConstPtr& foreground_msg,
77 const sensor_msgs::Image::ConstPtr& background_msg);
ros::Publisher pub_background_
boost::shared_ptr< GrabCut > Ptr
virtual void segment(const sensor_msgs::Image::ConstPtr &image_msg, const sensor_msgs::Image::ConstPtr &foreground_msg, const sensor_msgs::Image::ConstPtr &background_msg)
ros::Publisher pub_foreground_
virtual void unsubscribe()
ros::Publisher pub_foreground_mask_
message_filters::Subscriber< sensor_msgs::Image > sub_foreground_
message_filters::Subscriber< sensor_msgs::Image > sub_image_
virtual void updateDiagnostic(diagnostic_updater::DiagnosticStatusWrapper &stat)
boost::shared_ptr< dynamic_reconfigure::Server< Config > > srv_
bool use_probable_pixel_seed_
ros::Publisher pub_background_mask_
message_filters::Subscriber< sensor_msgs::Image > sub_background_
message_filters::sync_policies::ExactTime< sensor_msgs::Image, sensor_msgs::Image, sensor_msgs::Image > SyncPolicy
boost::shared_ptr< message_filters::Synchronizer< SyncPolicy > > sync_
virtual void configCallback(Config &config, uint32_t level)
jsk_perception
Author(s): Manabu Saito, Ryohei Ueda
autogenerated on Fri May 16 2025 03:11:17