Go to the documentation of this file.00001 #ifndef FACE_CONTOUR_DETECTOR_IMAGEFOREST_H_
00002 #define FACE_CONTOUR_DETECTOR_IMAGEFOREST_H_
00003
00004 #include <cassert>
00005
00006 #include <cv_bridge/CvBridge.h>
00007 #include <opencv/cv.h>
00008 #include <opencv/highgui.h>
00009 #include <map>
00010 #include <ros/assert.h>
00011
00012 namespace face_contour_detector {
00013
00015 class ImageForest {
00016 public:
00018 class Point {
00019 public:
00023 Point(int x, int y);
00026 Point(const Point& other);
00028 int x;
00030 int y;
00034 inline double Distance(Point other);
00035 };
00037 class Graph {
00038 public:
00040 Graph();
00043 Graph(const Graph& other);
00045 int id;
00047 int numPixels;
00049 std::vector<Point> endPoints;
00051 std::vector<Point> connectingPoints;
00052 };
00053
00054 public:
00056 ImageForest();
00060 ImageForest(const cv::Mat& mat, unsigned char threshold);
00062 virtual ~ImageForest();
00066 void ReadFromImage(const cv::Mat& mat, unsigned char threshold);
00069 inline int NumGraphs();
00070
00073 cv::Mat GenerateImage();
00077 void GenerateImage(cv::Mat& mat);
00078
00083 inline int GetGraphId(int x, int y);
00084
00088 inline int GetGraphId(ImageForest::Point point);
00089
00092 std::map<int, Graph> GetGraphs();
00093
00095 inline int Width();
00097 inline int Height();
00098
00101 double CallculateEdgyness();
00102
00105 double CallculateGraphMass();
00106
00107 private:
00108 int m_width;
00109 int m_height;
00110
00111 int m_lastId;
00112 int m_count;
00113 int* m_values;
00114
00115 void M_SetEqClass(int* eqMap, int size, int a, int b);
00116 inline void M_GetVectors(int x, int y, std::vector<ImageForest::Point>& vectors);
00117
00118 };
00119
00120
00121 inline int ImageForest::NumGraphs() { return m_count; }
00122 inline int ImageForest::GetGraphId(int x, int y) {
00123 ROS_ASSERT(m_values != 0);
00124 ROS_ASSERT(x >= 0 && x < m_width);
00125 ROS_ASSERT(y >= 0 && y < m_height);
00126 return m_values[y*m_width + x];
00127 }
00128 inline int ImageForest::GetGraphId(ImageForest::Point point) { return GetGraphId(point.x, point.y); }
00129 inline int ImageForest::Width() { return m_width; }
00130 inline int ImageForest::Height() { return m_height; }
00131 inline double ImageForest::Point::Distance(Point other) {
00132 double dx = x-other.x;
00133 double dy = y-other.y;
00134 return sqrt(dx*dx+dy*dy);
00135 }
00136 inline void ImageForest::M_GetVectors(int x, int y, std::vector<ImageForest::Point>& vectors) {
00137 for (int dy = y==0?0:-1; dy+y < Height() && dy <= 1; dy++) {
00138 for (int dx = x==0?0:-1; dx+x < Width() && dx <= 1; dx++) {
00139 if (GetGraphId(x+dx,y+dy) != 0) {
00140 vectors.push_back(ImageForest::Point(dx,dy));
00141 }
00142 }
00143 }
00144 }
00145
00146 }
00147
00148 #endif