NimbRo ROS Soccer Package
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Groups Pages
DistortionModel.hpp
1 //DistortionModel.hpp
2 // Created on: May 12, 2015
3 // Author: Hafez Farazi <farazi@ais.uni-bonn.de>
4 #pragma once
5 #include <opencv2/opencv.hpp>
6 #include <opencv2/highgui/highgui.hpp>
7 #include <ros/ros.h>
8 #include <vision_module/Tools/Parameters.hpp>
9 #include <vision_module/Tools/General.hpp>
10 
11 using namespace cv;
18 {
19 private:
20  void undistortP_slow(const vector<Point> contour,
21  vector<Point> &resCountour);
22  void ModifoedOpenCVUndistortPoint(const CvMat* _src, CvMat* _dst,
23  const CvMat* _cameraMatrix, const CvMat* _distCoeffs,
24  const CvMat* matR, const CvMat* matP);
25 
26  void ModifoedOpenCVUndistortPoint(InputArray _src, OutputArray _dst,
27  InputArray _cameraMatrix, InputArray _distCoeffs, InputArray _Rmat,
28  InputArray _Pmat);
29 
30  bool undistortP_normalized_slow(const vector<Point> contour,
31  vector<Point2f> &resCountour);
32  bool distortP_normalized_slow(const vector<Point3f> contour,
33  vector<Point2f> &resCountour);
34 
35 public:
36  vector<Point2f> distortionVector;
37  float getDiagonalAngleView();
38  Mat cameraMatrix, distCoeffs;
39  bool Init();
40  void CreateUndistort(const Mat &rawImg, Mat &res);
41  void CreateUndistortFull(const Mat &rawImg, Mat &res, Scalar bg);
42  bool UndistortP(const vector<Point> &contour, vector<Point> &resCountour);
43  bool UndistortP(const vector<Point> &contour, vector<Point2f> &resCountour);
44  bool UndistortP(const Point &inPoint, Point2f &resPoint);
45 
46  bool DistortP(const vector<Point> contour, vector<Point> &resCountour);
47 
48  bool DistortPFull(const vector<Point> contour, vector<Point> &resCountour);
49 };
50 
For undistortion.
Definition: DistortionModel.hpp:17