00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00036 #ifndef _DISTORTION_CORRECTION_H_
00037 #define _DISTORTION_CORRECTION_H_
00038
00039
00040
00043 #include <ros/ros.h>
00044
00045 #include <opencv2/imgproc/imgproc.hpp>
00046 #include <opencv2/highgui/highgui.hpp>
00047 #include <opencv2/core/core.hpp>
00048
00049 #include <mit_darpa_logs_player/camtrans.h>
00050
00051
00052 #include "camera_parameters.h"
00053
00054 class class_distortion_correction: virtual public class_camera_parameters
00055 {
00056
00057
00058
00059 public:
00060 class_distortion_correction(void){};
00061 ~class_distortion_correction(void){};
00062
00063 int correct_image_distortion(const cv::Mat* distorted, cv::Mat* corrected)
00064 {
00065 cv::Mat K;
00066 K.create(3,3,CV_64F);
00067
00068 K.at<double>(0,0) = intrinsic.at<double>(0,0);
00069 K.at<double>(0,1) = intrinsic.at<double>(0,1);
00070 K.at<double>(0,2) = intrinsic.at<double>(0,2);
00071
00072 K.at<double>(1,0) = intrinsic.at<double>(1,0);
00073 K.at<double>(1,1) = intrinsic.at<double>(1,1);
00074 K.at<double>(1,2) = intrinsic.at<double>(1,2);
00075
00076 K.at<double>(2,0) = intrinsic.at<double>(2,0);
00077 K.at<double>(2,1) = intrinsic.at<double>(2,1);
00078 K.at<double>(2,2) = intrinsic.at<double>(2,2);
00079
00080 cv::undistort(*distorted, *corrected, K, distortion);
00081 return 1;
00082 }
00083
00084
00085
00086 int correct_spherical_image_distortion(const cv::Mat* distorted, cv::Mat* corrected)
00087 {
00088
00089 double position[3];
00090 double orientation_quat[4];
00091
00092 CamTrans* cam = camtrans_new_spherical(spherical_distortion_params.calibration_width,
00093 spherical_distortion_params.calibration_height,
00094 intrinsic.at<double>(0,0),
00095 intrinsic.at<double>(1,1),
00096 intrinsic.at<double>(0,2),
00097 intrinsic.at<double>(1,2),
00098 0 ,
00099 position, orientation_quat,
00100 spherical_distortion_params.cx,
00101 spherical_distortion_params.cy,
00102 spherical_distortion_params.param);
00103
00104 camtrans_scale_image(cam, spherical_distortion_params.scale);
00105 cv::Mat mapx;
00106 mapx.create(240,376,CV_32FC1);
00107
00108 cv::Mat mapy;
00109 mapy.create(240,376,CV_32FC1);
00110
00111 for (double x=0; x<240; x++)
00112 for (double y=0; y<376; y++)
00113 {
00114 double ox,oy;
00115
00116 camtrans_distort_pixel(cam, y,x,&oy, &ox);
00117
00118 mapx.at<float>(x,y) = oy;
00119 mapy.at<float>(x,y) = ox;
00120 }
00121
00122 cv::remap(*distorted, *corrected, mapx, mapy,CV_INTER_LINEAR);
00123 return 1;
00124 }
00125 private:
00126
00127 };
00128
00129 #endif
00130