Perform background subtraction to extract the "moving" foreground. More...
#include <background_subtractor.h>
Classes | |
struct | Params |
Public Member Functions | |
void | apply (const cv::Mat &image, cv::Mat &fg_mask, int shift_x=0, int shift_y=0) |
Computes a foreground mask. | |
BackgroundSubtractor (const Params ¶meters) | |
Constructor that accepts a specific parameter configuration. | |
void | updateParameters (const Params ¶meters) |
Update internal parameters. | |
void | visualize (const std::string &name, const cv::Mat &image) |
OpenCV Visualization. | |
void | writeMatToYAML (const std::string &filename, const std::vector< cv::Mat > &mat_vec) |
Export vector of matrices to yaml file. | |
Private Member Functions | |
void | transformToCurrentFrame (int shift_x, int shift_y) |
Transform/shift all internal matrices/grids according to a given translation vector. | |
Private Attributes | |
cv::Mat | current_frame_ |
cv::Mat | occupancy_grid_fast_ |
cv::Mat | occupancy_grid_slow_ |
Params | params_ |
int | previous_shift_x_ |
int | previous_shift_y_ |
Perform background subtraction to extract the "moving" foreground.
This class is based on OpenCV's background subtraction class cv::BackgroundSubtractor. It has been modified in order to incorporate a specialized bandpass filter.
See http://docs.opencv.org/3.2.0/d7/df6/classcv_1_1BackgroundSubtractor.html for the original class.
Definition at line 57 of file background_subtractor.h.
BackgroundSubtractor::BackgroundSubtractor | ( | const Params & | parameters | ) |
Constructor that accepts a specific parameter configuration.
Definition at line 5 of file background_subtractor.cpp.
void BackgroundSubtractor::apply | ( | const cv::Mat & | image, |
cv::Mat & | fg_mask, | ||
int | shift_x = 0 , |
||
int | shift_y = 0 |
||
) |
Computes a foreground mask.
[in] | image | Next video frame |
[out] | fg_mask | Foreground mask as an 8-bit binary image |
[in] | shift_x | Translation along the x axis between the current and previous image |
[in] | shift_y | Translation along the y axis between the current and previous image |
Definition at line 9 of file background_subtractor.cpp.
void BackgroundSubtractor::transformToCurrentFrame | ( | int | shift_x, |
int | shift_y | ||
) | [private] |
Transform/shift all internal matrices/grids according to a given translation vector.
Definition at line 84 of file background_subtractor.cpp.
void BackgroundSubtractor::updateParameters | ( | const Params & | parameters | ) |
Update internal parameters.
Definition at line 112 of file background_subtractor.cpp.
void BackgroundSubtractor::visualize | ( | const std::string & | name, |
const cv::Mat & | image | ||
) |
OpenCV Visualization.
name | Id/name of the opencv window |
image | Image to be visualized |
Definition at line 101 of file background_subtractor.cpp.
void BackgroundSubtractor::writeMatToYAML | ( | const std::string & | filename, |
const std::vector< cv::Mat > & | mat_vec | ||
) |
Export vector of matrices to yaml file.
filename | Desired filename including path and excluding file suffix |
mat_vec | Vector of cv::Mat to be exported |
cv::Mat BackgroundSubtractor::current_frame_ [private] |
Definition at line 107 of file background_subtractor.h.
cv::Mat BackgroundSubtractor::occupancy_grid_fast_ [private] |
Definition at line 105 of file background_subtractor.h.
cv::Mat BackgroundSubtractor::occupancy_grid_slow_ [private] |
Definition at line 106 of file background_subtractor.h.
Params BackgroundSubtractor::params_ [private] |
Definition at line 112 of file background_subtractor.h.
int BackgroundSubtractor::previous_shift_x_ [private] |
Definition at line 109 of file background_subtractor.h.
int BackgroundSubtractor::previous_shift_y_ [private] |
Definition at line 110 of file background_subtractor.h.