43 #ifndef BACKGROUNDSUBTRACTOR_H_ 44 #define BACKGROUNDSUBTRACTOR_H_ 81 void apply(
const cv::Mat& image, cv::Mat& fg_mask,
int shift_x = 0,
int shift_y = 0);
88 void visualize(
const std::string& name,
const cv::Mat& image);
96 void writeMatToYAML(
const std::string& filename,
const std::vector<cv::Mat>& mat_vec);
115 #endif // BACKGROUNDSUBTRACTOR_H_ void apply(const cv::Mat &image, cv::Mat &fg_mask, int shift_x=0, int shift_y=0)
Computes a foreground mask.
cv::Mat occupancy_grid_fast_
double alpha_fast
Filter constant (learning rate) of the fast filter part.
void visualize(const std::string &name, const cv::Mat &image)
OpenCV Visualization.
double alpha_slow
Filter constant (learning rate) of the slow filter part.
double min_sep_between_fast_and_slow_filter
double max_occupancy_neighbors
void transformToCurrentFrame(int shift_x, int shift_y)
Transform/shift all internal matrices/grids according to a given translation vector.
cv::Mat occupancy_grid_slow_
Perform background subtraction to extract the "moving" foreground.
double min_occupancy_probability
void writeMatToYAML(const std::string &filename, const std::vector< cv::Mat > &mat_vec)
Export vector of matrices to yaml file.
BackgroundSubtractor(const Params ¶meters)
Constructor that accepts a specific parameter configuration.
void updateParameters(const Params ¶meters)
Update internal parameters.