Histogram based segmentation node. \ Using histogram backprojection, normalization, thresholding and dilate operator. \ Erode operator can be added by uncommenting lines \ in histogram_segmentation.cpp and the corresponding cfg file. More...
#include <pal_vision_segmentation/HistogramSegmentConfig.h>
#include <pal_vision_segmentation/image_processing.h>
#include <pal_vision_segmentation/histogram.h>
#include <ros/ros.h>
#include <image_transport/image_transport.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/image_encodings.h>
#include <dynamic_reconfigure/server.h>
#include <opencv2/core/core.hpp>
#include <opencv2/imgproc/imgproc.hpp>
#include <opencv2/highgui/highgui.hpp>
#include <opencv2/video/video.hpp>
#include <boost/filesystem.hpp>
Go to the source code of this file.
Functions | |
void | computeHistogramFromFile (const std::string &template_path, cv::MatND &hist) |
void | imageCb (const sensor_msgs::ImageConstPtr &msg) |
int | main (int argc, char *argv[]) |
void | reconf_callback (pal_vision_segmentation::HistogramSegmentConfig &config, uint32_t level) |
void | removeDarkPixels (const cv::Mat &originalImg, cv::Mat &binaryImg, int threshold=10) |
removeDarkPixels given a BGR image and a binary image computed from it, removes the white pixel in the latter corresponding to low luminosity pixels in the former one. | |
Variables | |
int | dark_pixels_threshold |
image_transport::Publisher | debug_pub |
int | dilate_iterations |
int | dilate_size |
int | erode_iterations |
int | erode_size |
image_transport::Publisher | image_pub |
cv::Mat | image_rect |
image_transport::Publisher | mask_pub |
cv::MatND | target_hist |
int | threshold |
Histogram based segmentation node. \ Using histogram backprojection, normalization, thresholding and dilate operator. \ Erode operator can be added by uncommenting lines \ in histogram_segmentation.cpp and the corresponding cfg file.
Definition in file histogram_segmentation.cpp.
void computeHistogramFromFile | ( | const std::string & | template_path, |
cv::MatND & | hist | ||
) |
Definition at line 197 of file histogram_segmentation.cpp.
void imageCb | ( | const sensor_msgs::ImageConstPtr & | msg | ) |
Definition at line 107 of file histogram_segmentation.cpp.
int main | ( | int | argc, |
char * | argv[] | ||
) |
Definition at line 256 of file histogram_segmentation.cpp.
void reconf_callback | ( | pal_vision_segmentation::HistogramSegmentConfig & | config, |
uint32_t | level | ||
) |
Definition at line 187 of file histogram_segmentation.cpp.
void removeDarkPixels | ( | const cv::Mat & | originalImg, |
cv::Mat & | binaryImg, | ||
int | threshold = 10 |
||
) |
removeDarkPixels given a BGR image and a binary image computed from it, removes the white pixel in the latter corresponding to low luminosity pixels in the former one.
[in] | originalImg | |
[out] | binaryImg | |
[in] | threshold |
Definition at line 89 of file histogram_segmentation.cpp.
Definition at line 74 of file histogram_segmentation.cpp.
Definition at line 77 of file histogram_segmentation.cpp.
Definition at line 70 of file histogram_segmentation.cpp.
int dilate_size |
Definition at line 71 of file histogram_segmentation.cpp.
int erode_iterations |
Definition at line 72 of file histogram_segmentation.cpp.
int erode_size |
Definition at line 73 of file histogram_segmentation.cpp.
Definition at line 76 of file histogram_segmentation.cpp.
cv::Mat image_rect |
Definition at line 75 of file histogram_segmentation.cpp.
Definition at line 68 of file histogram_segmentation.cpp.
cv::MatND target_hist |
Definition at line 78 of file histogram_segmentation.cpp.
int threshold |
Definition at line 69 of file histogram_segmentation.cpp.