distortion.h
Go to the documentation of this file.
1 #ifndef GAZEBO_PLUGINS_TEST_CAMERA_DISTORTION_H
2 #define GAZEBO_PLUGINS_TEST_CAMERA_DISTORTION_H
3 
4 // OpenCV includes
5 #include <opencv2/core/core.hpp>
6 #include <opencv2/imgproc/imgproc.hpp>
7 // undistort function has been moved to calib3d in opencv4
8 #include <opencv2/calib3d.hpp>
9 
10 // Test includes
11 #include <gtest/gtest.h>
12 
13 // ROS includes
14 #include <ros/ros.h>
16 #include <cv_bridge/cv_bridge.h>
17 
18 using namespace cv;
19 
20 void diffBetween(Mat& orig, Mat& diff, long& total_diff)
21 {
22  MatIterator_<Vec3b> it, end;
23  Vec3b orig_pixel, diff_pixel;
24  total_diff = 0;
25 
26  for(int i=0; i<orig.rows; i++)
27  {
28  for(int j=0; j<orig.cols; j++)
29  {
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]);
35  }
36  }
37 }
38 
39 class DistortionTest : public testing::Test
40 {
41  protected:
43 
44  // Used to listen for images
47 
48  // Stores found images
49  sensor_msgs::ImageConstPtr cam_image_distorted_;
50  sensor_msgs::ImageConstPtr cam_image_undistorted_;
51 
52  // Listens for camera metadata to be published
54  // Stores received camera metadata
55  sensor_msgs::CameraInfoConstPtr cam_info_distorted_;
56 
57  public:
58  void cameraDistortionTest();
59 
60  void imageCallback(const sensor_msgs::ImageConstPtr& msg, int cam_index)
61  {
62  // for now, only support 2 cameras
63  assert(cam_index == 0 || cam_index == 1);
64  if(cam_index == 0)
65  {
66  cam_image_undistorted_ = msg;
67  }
68  else
69  {
70  cam_image_distorted_ = msg;
71  }
72  }
73  void camInfoCallback(const sensor_msgs::CameraInfoConstPtr& msg)
74  {
75  cam_info_distorted_ = msg;
76  }
77 };
78 
80 {
82  spinner.start();
83 
85  cam_sub_undistorted_ =
86  trans.subscribe("/camera_undistorted/image_raw",
87  1,
88  boost::bind(&DistortionTest::imageCallback,
89  dynamic_cast<DistortionTest*>(this), boost::placeholders::_1, 0)
90  );
91 
92  cam_info_distorted_ = nullptr;
93  cam_image_distorted_ = nullptr;
94  // acquire information from ROS topics
95  cam_sub_distorted_ =
96  trans.subscribe("/camera_distorted/image_raw",
97  1,
98  boost::bind(&DistortionTest::imageCallback,
99  dynamic_cast<DistortionTest*>(this), boost::placeholders::_1, 1)
100  );
101  cam_info_distorted_sub_ =
102  nh_.subscribe("/camera_distorted/camera_info",
103  1,
105  dynamic_cast<DistortionTest*>(this)
106  );
107 
108  // keep waiting until we have an image
109 
110  if(cam_info_distorted_ && cam_image_distorted_) {
111  std::cerr << "available immediately" << std::endl;
112  }
113  while (!cam_info_distorted_ ||
114  !cam_image_distorted_ ||
115  !cam_image_undistorted_)
116  {
117  ros::Duration(0.1).sleep();
118  }
119  cam_sub_undistorted_.shutdown();
120  cam_sub_distorted_.shutdown();
121  cam_info_distorted_sub_.shutdown();
122 
123  // load camera coefficients from published ROS information
124  Mat intrinsic_distorted_matrix = Mat(3, 3, CV_64F);
125  if(cam_info_distorted_->K.size() == 9)
126  {
127  memcpy(intrinsic_distorted_matrix.data, cam_info_distorted_->K.data(),
128  cam_info_distorted_->K.size()*sizeof(double));
129  }
130  Mat distortion_coeffs = Mat(5, 1, CV_64F);
131  if(cam_info_distorted_->D.size() == 5)
132  {
133  memcpy(distortion_coeffs.data, cam_info_distorted_->D.data(),
134  cam_info_distorted_->D.size()*sizeof(double));
135  }
136 
137  // Information acquired, now test the quality of the undistortion
138 
139  Mat distorted = Mat(cv_bridge::toCvCopy(cam_image_distorted_)->image);
140  Mat fixed = distorted.clone();
141  Mat undistorted = Mat(cv_bridge::toCvCopy(cam_image_undistorted_)->image);
142 
143  //crop the image to remove black borders leftover from (un)distortion
144  int cropBorder = 50;
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);
149 
150 
151  undistort(distorted, fixed, intrinsic_distorted_matrix, distortion_coeffs);
152 
153  //Ensure that we didn't crop away everything
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);
160 
161  // The difference between the undistorted image and the no-distortion camera
162  // image should be the lowest when we use the correct distortion parameters.
163  long diff1 = 0, diff2 = 0;
164  diffBetween(fixed_crop, undistorted_crop, diff1);
165 
166  const double OFFSET = 0.01;
167 
168  // test each parameter, varying one at a time
169  for(size_t i = 0; i < 5; ++i)
170  {
171  distortion_coeffs.at<double>(i,0) += OFFSET;
172  undistort(distorted, fixed, intrinsic_distorted_matrix, distortion_coeffs);
173  diffBetween(fixed_crop, undistorted_crop, diff2);
174  EXPECT_GE(diff2, diff1);
175  distortion_coeffs.at<double>(i,0) -= OFFSET;
176 
177  distortion_coeffs.at<double>(i,0) -= OFFSET;
178  undistort(distorted, fixed, intrinsic_distorted_matrix, distortion_coeffs);
179  diffBetween(fixed_crop, undistorted_crop, diff2);
180  EXPECT_GE(diff2, diff1);
181  distortion_coeffs.at<double>(i,0) += OFFSET;
182  }
183 }
184 
185 #endif
msg
msg
DistortionTest::imageCallback
void imageCallback(const sensor_msgs::ImageConstPtr &msg, int cam_index)
Definition: distortion.h:60
image_transport::ImageTransport
diffBetween
void diffBetween(Mat &orig, Mat &diff, long &total_diff)
Definition: distortion.h:20
DistortionTest::cam_info_distorted_sub_
ros::Subscriber cam_info_distorted_sub_
Definition: distortion.h:53
ros.h
ros::AsyncSpinner
DistortionTest::camInfoCallback
void camInfoCallback(const sensor_msgs::CameraInfoConstPtr &msg)
Definition: distortion.h:73
image_transport::Subscriber
spinner
void spinner()
DistortionTest::cam_image_distorted_
sensor_msgs::ImageConstPtr cam_image_distorted_
Definition: distortion.h:49
cv_bridge::toCvCopy
CvImagePtr toCvCopy(const sensor_msgs::CompressedImage &source, const std::string &encoding=std::string())
image_transport::ImageTransport::subscribe
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
DistortionTest::cam_info_distorted_
sensor_msgs::CameraInfoConstPtr cam_info_distorted_
Definition: distortion.h:55
DistortionTest::cameraDistortionTest
void cameraDistortionTest()
Definition: distortion.h:79
image_transport.h
DistortionTest::nh_
ros::NodeHandle nh_
Definition: distortion.h:42
DistortionTest
Definition: distortion.h:39
cv_bridge.h
DistortionTest::cam_image_undistorted_
sensor_msgs::ImageConstPtr cam_image_undistorted_
Definition: distortion.h:50
DistortionTest::cam_sub_distorted_
image_transport::Subscriber cam_sub_distorted_
Definition: distortion.h:45
ros::Duration::sleep
bool sleep() const
ros::Duration
DistortionTest::cam_sub_undistorted_
image_transport::Subscriber cam_sub_undistorted_
Definition: distortion.h:46
ros::NodeHandle
ros::Subscriber


gazebo_plugins
Author(s): John Hsu
autogenerated on Thu Sep 5 2024 02:49:55