NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
radtan_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_RADTAN_DISTORTER_H_
19 #define VISION_COMMON_RADTAN_DISTORTER_H_
20 
23 
24 #include <Eigen/Core>
25 
26 #include <opencv2/core/eigen.hpp>
27 
28 #include <ceres/ceres.h>
29 
30 namespace vision_common {
31 class RadTanDistorter : public Distorter<4, RadTanDistorter> {
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  const T& k1 = distortion[0];
40  const T& k2 = distortion[1];
41  const T& p1 = distortion[2];
42  const T& p2 = distortion[3];
43  // TODO(rsoussan): Support 5 distortion params
44  const T k3(0.0);
45 
46  const Eigen::Matrix<T, 2, 1> relative_coordinates = RelativeCoordinates(undistorted_point, intrinsics);
47  const T& relative_x = relative_coordinates[0];
48  const T& relative_y = relative_coordinates[1];
49  // Squared norm
50  const T r2 = relative_x * relative_x + relative_y * relative_y;
51 
52  // Apply radial distortion
53  const T radial_distortion_coeff = 1.0 + k1 * r2 + k2 * r2 * r2 + k3 * r2 * r2 * r2;
54  T distorted_relative_x = relative_x * radial_distortion_coeff;
55  T distorted_relative_y = relative_y * radial_distortion_coeff;
56 
57  // Apply tangential distortion
58  distorted_relative_x =
59  distorted_relative_x + (2.0 * p1 * relative_x * relative_y + p2 * (r2 + 2.0 * relative_x * relative_x));
60  distorted_relative_y =
61  distorted_relative_y + (p1 * (r2 + 2.0 * relative_y * relative_y) + 2.0 * p2 * relative_x * relative_y);
62 
63  return AbsoluteCoordinates(Eigen::Matrix<T, 2, 1>(distorted_relative_x, distorted_relative_y), intrinsics);
64  }
65 
66  cv::Mat Undistort(const cv::Mat& distorted_image, const Eigen::Matrix3d& intrinsics,
67  const Eigen::VectorXd& distortion) const final {
68  cv::Mat undistorted_image;
69  cv::Mat intrinsics_mat;
70  cv::eigen2cv(intrinsics, intrinsics_mat);
71  cv::Mat distortion_vector;
72  cv::eigen2cv(distortion, distortion_vector);
73  cv::undistort(distorted_image, undistorted_image, intrinsics_mat, distortion_vector);
74  return undistorted_image;
75  }
76 
77  Eigen::Vector2d Undistort(const Eigen::Vector2d& distorted_point, const Eigen::Matrix3d& intrinsics,
78  const Eigen::VectorXd& distortion) const final {
79  cv::Mat intrinsics_mat;
80  cv::eigen2cv(intrinsics, intrinsics_mat);
81  cv::Mat distortion_vector;
82  cv::eigen2cv(distortion, distortion_vector);
83  cv::Mat distorted_point_vector;
84  cv::eigen2cv(distorted_point, distorted_point_vector);
85  cv::Mat undistorted_point_vector;
86  cv::undistort(distorted_point_vector, undistorted_point_vector, intrinsics_mat, distortion_vector);
87  Eigen::Vector2d undistorted_point;
88  cv::cv2eigen(undistorted_point_vector, undistorted_point);
89  return undistorted_point;
90  }
91 };
92 } // namespace vision_common
93 
94 #endif // VISION_COMMON_RADTAN_DISTORTER_H_
vision_common
Definition: brisk_feature_detector_and_matcher.h:25
vision_common::RadTanDistorter::Undistort
Eigen::Vector2d Undistort(const Eigen::Vector2d &distorted_point, const Eigen::Matrix3d &intrinsics, const Eigen::VectorXd &distortion) const final
Definition: radtan_distorter.h:77
vision_common::Distorter
Definition: distorter.h:29
vision_common::RadTanDistorter
Definition: radtan_distorter.h:31
vision_common::RadTanDistorter::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: radtan_distorter.h:37
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::RadTanDistorter::Undistort
cv::Mat Undistort(const cv::Mat &distorted_image, const Eigen::Matrix3d &intrinsics, const Eigen::VectorXd &distortion) const final
Definition: radtan_distorter.h:66
utilities.h
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