1 #ifndef GAZEBO_PLUGINS_TEST_CAMERA_DISTORTION_H
2 #define GAZEBO_PLUGINS_TEST_CAMERA_DISTORTION_H
5 #include <opencv2/core/core.hpp>
6 #include <opencv2/imgproc/imgproc.hpp>
8 #include <opencv2/calib3d.hpp>
11 #include <gtest/gtest.h>
22 MatIterator_<Vec3b> it, end;
23 Vec3b orig_pixel, diff_pixel;
26 for(
int i=0; i<orig.rows; i++)
28 for(
int j=0; j<orig.cols; j++)
30 orig_pixel = orig.at<cv::Vec3b>(i,j);
31 diff_pixel = diff.at<cv::Vec3b>(i,j);
32 total_diff += abs(orig_pixel[0] - diff_pixel[0]) +
33 abs(orig_pixel[1] - diff_pixel[1]) +
34 abs(orig_pixel[2] - diff_pixel[2]);
58 void cameraDistortionTest();
60 void imageCallback(
const sensor_msgs::ImageConstPtr& msg,
int cam_index)
63 assert(cam_index == 0 || cam_index == 1);
66 cam_image_undistorted_ =
msg;
70 cam_image_distorted_ =
msg;
75 cam_info_distorted_ =
msg;
85 cam_sub_undistorted_ =
86 trans.
subscribe(
"/camera_undistorted/image_raw",
92 cam_info_distorted_ =
nullptr;
93 cam_image_distorted_ =
nullptr;
96 trans.
subscribe(
"/camera_distorted/image_raw",
101 cam_info_distorted_sub_ =
102 nh_.subscribe(
"/camera_distorted/camera_info",
110 if(cam_info_distorted_ && cam_image_distorted_) {
111 std::cerr <<
"available immediately" << std::endl;
113 while (!cam_info_distorted_ ||
114 !cam_image_distorted_ ||
115 !cam_image_undistorted_)
119 cam_sub_undistorted_.shutdown();
120 cam_sub_distorted_.shutdown();
121 cam_info_distorted_sub_.shutdown();
124 Mat intrinsic_distorted_matrix = Mat(3, 3, CV_64F);
125 if(cam_info_distorted_->K.size() == 9)
127 memcpy(intrinsic_distorted_matrix.data, cam_info_distorted_->K.data(),
128 cam_info_distorted_->K.size()*
sizeof(
double));
130 Mat distortion_coeffs = Mat(5, 1, CV_64F);
131 if(cam_info_distorted_->D.size() == 5)
133 memcpy(distortion_coeffs.data, cam_info_distorted_->D.data(),
134 cam_info_distorted_->D.size()*
sizeof(
double));
140 Mat fixed = distorted.clone();
145 cv::Rect myROI(cropBorder, cropBorder,
146 fixed.rows - 2 * cropBorder, fixed.cols - 2 * cropBorder);
147 cv::Mat fixed_crop = fixed(myROI);
148 cv::Mat undistorted_crop = undistorted(myROI);
151 undistort(distorted, fixed, intrinsic_distorted_matrix, distortion_coeffs);
154 ASSERT_GT(distorted.rows, 0);
155 ASSERT_GT(distorted.cols, 0);
156 ASSERT_GT(undistorted.rows, 0);
157 ASSERT_GT(undistorted.cols, 0);
158 ASSERT_GT(fixed.rows, 0);
159 ASSERT_GT(fixed.cols, 0);
163 long diff1 = 0, diff2 = 0;
166 const double OFFSET = 0.01;
169 for(
size_t i = 0; i < 5; ++i)
171 distortion_coeffs.at<
double>(i,0) += OFFSET;
172 undistort(distorted, fixed, intrinsic_distorted_matrix, distortion_coeffs);
174 EXPECT_GE(diff2, diff1);
175 distortion_coeffs.at<
double>(i,0) -= OFFSET;
177 distortion_coeffs.at<
double>(i,0) -= OFFSET;
178 undistort(distorted, fixed, intrinsic_distorted_matrix, distortion_coeffs);
180 EXPECT_GE(diff2, diff1);
181 distortion_coeffs.at<
double>(i,0) += OFFSET;