Public Member Functions | |
BGFGCodeBook (ros::NodeHandle &n) | |
void | help (void) |
void | imageCallback (const sensor_msgs::ImageConstPtr &msg_ptr) |
~BGFGCodeBook () | |
Protected Attributes | |
sensor_msgs::CvBridge | bridge_ |
int | c_ |
int | cbBounds_ |
bool | ch_ [3] |
ros::ServiceClient | cl |
bool | first_image |
image_transport::Subscriber | image_sub_ |
IplImage * | ImaskCodeBook_ |
IplImage * | ImaskCodeBookCC_ |
std::string | input_image_topic_ |
image_transport::ImageTransport | it_ |
CvBGCodeBookModel * | model_ |
int | modMax_ |
int | modMin_ |
int | n_ |
int | nChannels_ |
int | nframes_ |
int | nframesToLearnBG_ |
ros::NodeHandle | nh_ |
std::string | output_topic_ |
bool | pause_ |
ros::Publisher | pub |
IplImage * | rawImage_ |
bool | singlestep_ |
IplImage * | yuvImage_ |
Definition at line 49 of file roi_bgfg_codebooks.cpp.
BGFGCodeBook::BGFGCodeBook | ( | ros::NodeHandle & | n | ) | [inline] |
Definition at line 53 of file roi_bgfg_codebooks.cpp.
BGFGCodeBook::~BGFGCodeBook | ( | ) | [inline] |
Definition at line 91 of file roi_bgfg_codebooks.cpp.
void BGFGCodeBook::help | ( | void | ) | [inline] |
Definition at line 98 of file roi_bgfg_codebooks.cpp.
void BGFGCodeBook::imageCallback | ( | const sensor_msgs::ImageConstPtr & | msg_ptr | ) | [inline] |
Definition at line 124 of file roi_bgfg_codebooks.cpp.
sensor_msgs::CvBridge BGFGCodeBook::bridge_ [protected] |
Definition at line 333 of file roi_bgfg_codebooks.cpp.
int BGFGCodeBook::c_ [protected] |
Definition at line 344 of file roi_bgfg_codebooks.cpp.
int BGFGCodeBook::cbBounds_ [protected] |
Definition at line 339 of file roi_bgfg_codebooks.cpp.
bool BGFGCodeBook::ch_[3] [protected] |
Definition at line 341 of file roi_bgfg_codebooks.cpp.
ros::ServiceClient BGFGCodeBook::cl [protected] |
Definition at line 332 of file roi_bgfg_codebooks.cpp.
bool BGFGCodeBook::first_image [protected] |
Definition at line 348 of file roi_bgfg_codebooks.cpp.
image_transport::Subscriber BGFGCodeBook::image_sub_ [protected] |
Definition at line 330 of file roi_bgfg_codebooks.cpp.
IplImage* BGFGCodeBook::ImaskCodeBook_ [protected] |
Definition at line 343 of file roi_bgfg_codebooks.cpp.
IplImage * BGFGCodeBook::ImaskCodeBookCC_ [protected] |
Definition at line 343 of file roi_bgfg_codebooks.cpp.
std::string BGFGCodeBook::input_image_topic_ [protected] |
Definition at line 334 of file roi_bgfg_codebooks.cpp.
image_transport::ImageTransport BGFGCodeBook::it_ [protected] |
Definition at line 329 of file roi_bgfg_codebooks.cpp.
CvBGCodeBookModel* BGFGCodeBook::model_ [protected] |
Definition at line 338 of file roi_bgfg_codebooks.cpp.
int BGFGCodeBook::modMax_ [protected] |
Definition at line 339 of file roi_bgfg_codebooks.cpp.
int BGFGCodeBook::modMin_ [protected] |
Definition at line 339 of file roi_bgfg_codebooks.cpp.
int BGFGCodeBook::n_ [protected] |
Definition at line 344 of file roi_bgfg_codebooks.cpp.
int BGFGCodeBook::nChannels_ [protected] |
Definition at line 344 of file roi_bgfg_codebooks.cpp.
int BGFGCodeBook::nframes_ [protected] |
Definition at line 344 of file roi_bgfg_codebooks.cpp.
int BGFGCodeBook::nframesToLearnBG_ [protected] |
Definition at line 345 of file roi_bgfg_codebooks.cpp.
ros::NodeHandle BGFGCodeBook::nh_ [protected] |
Definition at line 328 of file roi_bgfg_codebooks.cpp.
std::string BGFGCodeBook::output_topic_ [protected] |
Definition at line 335 of file roi_bgfg_codebooks.cpp.
bool BGFGCodeBook::pause_ [protected] |
Definition at line 346 of file roi_bgfg_codebooks.cpp.
ros::Publisher BGFGCodeBook::pub [protected] |
Definition at line 331 of file roi_bgfg_codebooks.cpp.
IplImage* BGFGCodeBook::rawImage_ [protected] |
Definition at line 342 of file roi_bgfg_codebooks.cpp.
bool BGFGCodeBook::singlestep_ [protected] |
Definition at line 347 of file roi_bgfg_codebooks.cpp.
IplImage * BGFGCodeBook::yuvImage_ [protected] |
Definition at line 342 of file roi_bgfg_codebooks.cpp.