NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
fov_distorter.h
Go to the documentation of this file.
1 /* Copyright (c) 2017, United States Government, as represented by the
2  * Administrator of the National Aeronautics and Space Administration.
3  *
4  * All rights reserved.
5  *
6  * The Astrobee platform is licensed under the Apache License, Version 2.0
7  * (the "License"); you may not use this file except in compliance with the
8  * License. You may obtain a copy of the License at
9  *
10  * http://www.apache.org/licenses/LICENSE-2.0
11  *
12  * Unless required by applicable law or agreed to in writing, software
13  * distributed under the License is distributed on an "AS IS" BASIS, WITHOUT
14  * WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. See the
15  * License for the specific language governing permissions and limitations
16  * under the License.
17  */
18 #ifndef VISION_COMMON_FOV_DISTORTER_H_
19 #define VISION_COMMON_FOV_DISTORTER_H_
20 
23 
24 #include <Eigen/Core>
25 
26 #include <opencv2/opencv.hpp>
27 
28 #include <ceres/ceres.h>
29 
30 namespace vision_common {
31 class FovDistorter : public Distorter<1, FovDistorter> {
32  public:
35 
36  template <typename T>
37  Eigen::Matrix<T, 2, 1> Distort(const T* distortion, const Eigen::Matrix<T, 3, 3>& intrinsics,
38  const Eigen::Matrix<T, 2, 1>& undistorted_point) const {
39  // Distortion model expects image coordinates to be in relative coordinates
40  const Eigen::Matrix<T, 2, 1> relative_coordinates = RelativeCoordinates(undistorted_point, intrinsics);
41  const T& relative_x = relative_coordinates[0];
42  const T& relative_y = relative_coordinates[1];
43 
44  // Squared norm
45  const T r2 = relative_x * relative_x + relative_y * relative_y;
46  const T& w = distortion[0];
47  T warping;
48  if (r2 > 1e-5) {
49  const T a = 2.0 * ceres::tan(w / 2.0);
50  const T b = ceres::atan(r2 * a) / w;
51  warping = b / r2;
52  } else {
53  warping = T(1.0);
54  }
55  const T distorted_relative_x = warping * relative_x;
56  const T distorted_relative_y = warping * relative_y;
57  return AbsoluteCoordinates(Eigen::Matrix<T, 2, 1>(distorted_relative_x, distorted_relative_y), intrinsics);
58  }
59 
60  cv::Mat Undistort(const cv::Mat& distorted_image, const Eigen::Matrix3d& intrinsics,
61  const Eigen::VectorXd& distortion) const final {
62  cv::Mat gray_distorted_image;
63  cv::cvtColor(distorted_image, gray_distorted_image, cv::COLOR_BGRA2GRAY);
64  cv::Mat undistorted_image(distorted_image.size(), CV_8UC1, cv::Scalar(0));
65  for (int y = 0; y < undistorted_image.rows; ++y) {
66  for (int x = 0; x < undistorted_image.cols; ++x) {
67  const uchar pixel_val = gray_distorted_image.at<uchar>(y, x);
68  const Eigen::Vector2d undistorted_point = Undistort(Eigen::Vector2d(x, y), intrinsics, distortion);
69  const Eigen::Vector2i undistorted_rounded_point(std::round(undistorted_point[0]),
70  std::round(undistorted_point[1]));
71  if (undistorted_rounded_point.x() >= undistorted_image.cols || undistorted_rounded_point.x() < 0) continue;
72  if (undistorted_rounded_point.y() >= undistorted_image.rows || undistorted_rounded_point.y() < 0) continue;
73  undistorted_image.at<uchar>(undistorted_rounded_point.y(), undistorted_rounded_point.x()) = pixel_val;
74  }
75  }
76  return undistorted_image;
77  }
78 
79  Eigen::Vector2d Undistort(const Eigen::Vector2d& distorted_point, const Eigen::Matrix3d& intrinsics,
80  const Eigen::VectorXd& distortion) const final {
81  const Eigen::Vector2d relative_distorted_point = RelativeCoordinates(distorted_point, intrinsics);
82  const double rd = relative_distorted_point.norm();
83  const double a = 2.0 * std::tan(distortion[0] / 2.0);
84  const double ru = std::tan(rd * distortion[0]) / a;
85  const double unwarping = rd > 1e-5 ? ru / rd : 1.0;
86  const Eigen::Vector2d relative_undistorted_point = unwarping * relative_distorted_point;
87  const Eigen::Vector2d undistorted_point = AbsoluteCoordinates(relative_undistorted_point, intrinsics);
88  return undistorted_point;
89  }
90 };
91 } // namespace vision_common
92 
93 #endif // VISION_COMMON_FOV_DISTORTER_H_
vision_common
Definition: brisk_feature_detector_and_matcher.h:25
vision_common::Distorter
Definition: distorter.h:29
distorter.h
vision_common::RelativeCoordinates
Eigen::Matrix< T, 2, 1 > RelativeCoordinates(const Eigen::Matrix< T, 2, 1 > &absolute_point, const Eigen::Matrix< T, 3, 3 > &intrinsics)
Definition: utilities.h:70
vision_common::FovDistorter::Undistort
Eigen::Vector2d Undistort(const Eigen::Vector2d &distorted_point, const Eigen::Matrix3d &intrinsics, const Eigen::VectorXd &distortion) const final
Definition: fov_distorter.h:79
utilities.h
vision_common::FovDistorter::Undistort
cv::Mat Undistort(const cv::Mat &distorted_image, const Eigen::Matrix3d &intrinsics, const Eigen::VectorXd &distortion) const final
Definition: fov_distorter.h:60
vision_common::FovDistorter::Distort
Eigen::Matrix< T, 2, 1 > Distort(const T *distortion, const Eigen::Matrix< T, 3, 3 > &intrinsics, const Eigen::Matrix< T, 2, 1 > &undistorted_point) const
Definition: fov_distorter.h:37
vision_common::AbsoluteCoordinates
Eigen::Matrix< T, 2, 1 > AbsoluteCoordinates(const Eigen::Matrix< T, 2, 1 > &relative_point, const Eigen::Matrix< T, 3, 3 > &intrinsics)
Definition: utilities.h:85
vision_common::FovDistorter
Definition: fov_distorter.h:31