#include <background_substraction.h>
Public Types | |
typedef jsk_perception::BackgroundSubstractionConfig | Config |
Public Member Functions | |
BackgroundSubstraction () | |
Protected Member Functions | |
virtual void | configCallback (Config &config, uint32_t level) |
virtual void | onInit () |
virtual void | subscribe () |
virtual void | substract (const sensor_msgs::Image::ConstPtr &image_msg) |
virtual void | unsubscribe () |
virtual void | updateDiagnostic (diagnostic_updater::DiagnosticStatusWrapper &stat) |
Protected Attributes | |
double | background_ratio_ |
cv::BackgroundSubtractorMOG2 | bg_ |
bool | detect_shadows_ |
ros::Publisher | image_pub_ |
boost::shared_ptr < image_transport::ImageTransport > | it_ |
boost::mutex | mutex_ |
int | nmixtures_ |
boost::shared_ptr < dynamic_reconfigure::Server < Config > > | srv_ |
image_transport::Subscriber | sub_ |
Definition at line 54 of file background_substraction.h.
typedef jsk_perception::BackgroundSubstractionConfig jsk_perception::BackgroundSubstraction::Config |
Definition at line 58 of file background_substraction.h.
Definition at line 57 of file background_substraction.h.
void jsk_perception::BackgroundSubstraction::configCallback | ( | Config & | config, |
uint32_t | level | ||
) | [protected, virtual] |
Definition at line 57 of file background_substraction_nodelet.cpp.
void jsk_perception::BackgroundSubstraction::onInit | ( | ) | [protected, virtual] |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 42 of file background_substraction_nodelet.cpp.
void jsk_perception::BackgroundSubstraction::subscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 88 of file background_substraction_nodelet.cpp.
void jsk_perception::BackgroundSubstraction::substract | ( | const sensor_msgs::Image::ConstPtr & | image_msg | ) | [protected, virtual] |
Definition at line 115 of file background_substraction_nodelet.cpp.
void jsk_perception::BackgroundSubstraction::unsubscribe | ( | ) | [protected, virtual] |
Implements jsk_topic_tools::ConnectionBasedNodelet.
Definition at line 96 of file background_substraction_nodelet.cpp.
void jsk_perception::BackgroundSubstraction::updateDiagnostic | ( | diagnostic_updater::DiagnosticStatusWrapper & | stat | ) | [protected, virtual] |
Reimplemented from jsk_topic_tools::DiagnosticNodelet.
Definition at line 101 of file background_substraction_nodelet.cpp.
double jsk_perception::BackgroundSubstraction::background_ratio_ [protected] |
Definition at line 91 of file background_substraction.h.
cv::BackgroundSubtractorMOG2 jsk_perception::BackgroundSubstraction::bg_ [protected] |
Definition at line 87 of file background_substraction.h.
bool jsk_perception::BackgroundSubstraction::detect_shadows_ [protected] |
Definition at line 89 of file background_substraction.h.
Definition at line 74 of file background_substraction.h.
boost::shared_ptr<image_transport::ImageTransport> jsk_perception::BackgroundSubstraction::it_ [protected] |
Definition at line 76 of file background_substraction.h.
boost::mutex jsk_perception::BackgroundSubstraction::mutex_ [protected] |
Definition at line 78 of file background_substraction.h.
int jsk_perception::BackgroundSubstraction::nmixtures_ [protected] |
Definition at line 90 of file background_substraction.h.
boost::shared_ptr<dynamic_reconfigure::Server<Config> > jsk_perception::BackgroundSubstraction::srv_ [protected] |
Definition at line 77 of file background_substraction.h.
Definition at line 75 of file background_substraction.h.