NimbRo ROS Soccer Package
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
SortFuntions.hpp
1 //SortFuntions.hpp
2 // Created on: May 15, 2015
3 // Author: Hafez Farazi <farazi@ais.uni-bonn.de>
4 #pragma once
5 #include <opencv2/opencv.hpp>
6 #include <math.h>
7 #include <vision_module/Tools/Parameters.hpp>
8 #include <vision_module/Tools/General.hpp>
9 #include <vision_module/Projections/CameraProjections.hpp>
10 #include <vision_module/SoccerObjects/IDetector.hpp>
11 #include <algorithm> // std::sort
12 using namespace cv;
13 
14 bool SortFuncDescending(vector<Point> i, vector<Point> j);
15 
16 bool SortFuncDistanceAcending(vector<Point> i, vector<Point> j,CameraProjections &projecttion);
17 
23 class sorter {
24  CameraProjections *projecttion;
25 public:
26  sorter(CameraProjections *projecttion) : projecttion(projecttion) {}
27  bool operator()(vector<Point> o1, vector<Point> o2) {
28 
29  Point2f iR,jR;
30  bool res=projecttion->GetOnRealCordinate_single(minAreaRect(o1).center,iR);
31  res&=projecttion->GetOnRealCordinate_single(minAreaRect(o2).center,jR);
32  if(!res)
33  {
34  ROS_ERROR("Error in programming!");
35  }
36 
37  return GetDistance(iR) < GetDistance(jR);
38 
39  }
40  bool operator()(Rect o1, Rect o2) {
41 
42  Point2f iR,jR;
43 
44  bool res=projecttion->GetOnRealCordinate_single(GetCenter(o1),iR);
45  res&=projecttion->GetOnRealCordinate_single(GetCenter(o2),jR);
46  if(!res)
47  {
48  ROS_ERROR("Error in programming!");
49  }
50 
51  return GetDistance(iR) < GetDistance(jR);
52 
53  }
54 };
55 
For pixel projections.
Definition: CameraProjections.hpp:50
For sorting operations on custom objects.
Definition: SortFuntions.hpp:23