NASA Astrobee Robot Software  0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
reprojection.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 SPARSE_MAPPING_REPROJECTION_H_
19 #define SPARSE_MAPPING_REPROJECTION_H_
20 
21 #include <Eigen/Geometry>
23 #include <ceres/ceres.h>
24 
25 #include <map>
26 #include <vector>
27 #include <limits>
28 #include <string>
29 #include <set>
30 
31 namespace camera {
32  class CameraModel;
33 }
34 
35 namespace cv {
36  template <class T>
37  class Point_;
38  template <class T>
39  class Point3_;
40  typedef Point_<double> Point2d;
42 }
43 
44 namespace sparse_mapping {
45 
46  ceres::LossFunction* GetLossFunction(std::string cost_fun, double th);
47 
61 void BundleAdjust(std::vector<std::map<int, int> > const& pid_to_cid_fid,
62  std::vector<Eigen::Matrix2Xd > const& cid_to_keypoint_map,
63  double focal_length,
64  std::vector<Eigen::Affine3d> * cid_to_cam_t_global,
65  std::vector<Eigen::Vector3d> * pid_to_xyz,
66  std::vector<std::map<int, int> > const& user_pid_to_cid_fid,
67  std::vector<Eigen::Matrix2Xd > const& user_cid_to_keypoint_map,
68  std::vector<Eigen::Vector3d> * user_pid_to_xyz,
69  ceres::LossFunction * loss,
70  ceres::Solver::Options const& options,
71  ceres::Solver::Summary* summary,
72  int first = 0, int last = std::numeric_limits<int>::max(),
73  bool fix_cameras = false,
74  std::set<int> const& fixed_cameras = std::set<int>());
75 
84 void BundleAdjustSmallSet(std::vector<Eigen::Matrix2Xd> const& features_n,
85  double focal_length,
86  std::vector<Eigen::Affine3d> * cam_t_global_n,
87  Eigen::Matrix3Xd * pid_to_xyz,
88  ceres::LossFunction * loss,
89  ceres::Solver::Options const& options,
90  ceres::Solver::Summary * summary);
91 
92 // Random integer between min (inclusive) and max (exclusive)
93 int RandomInt(int min, int max);
94 
95 // Select a Random Observations
96 void SelectRandomObservations(const std::vector<Eigen::Vector3d> & all_landmarks,
97  const std::vector<Eigen::Vector2d> & all_observations, size_t num_selected,
98  std::vector<cv::Point3d> * landmarks, std::vector<cv::Point2d> * observations);
99 
100 // Used to find landmark and observations that best match the current camera
101 // model.
102 size_t CountInliers(const std::vector<Eigen::Vector3d> & landmarks,
103  const std::vector<Eigen::Vector2d> & observations,
104  const camera::CameraModel & camera, int tolerance,
105  std::vector<size_t>* inliers);
106 
116 void EstimateCamera(camera::CameraModel * camera_estimate, std::vector<Eigen::Vector3d> * landmarks,
117  const std::vector<Eigen::Vector2d> & observations,
118  const ceres::Solver::Options & options, ceres::Solver::Summary* summary);
119 
129 int RansacEstimateCamera(const std::vector<Eigen::Vector3d> & landmarks,
130  const std::vector<Eigen::Vector2d> & observations,
131  int num_tries, int inlier_tolerance, camera::CameraModel * camera_estimate,
132  std::vector<Eigen::Vector3d> * inlier_landmarks_out = NULL,
133  std::vector<Eigen::Vector2d> * inlier_observations_out = NULL,
134  bool verbose = false);
135 
136 // ICP solver that given matching 3D points, finds an affine transform that
137 // best fits in to out.
138 void Find3DAffineTransform(Eigen::Matrix3Xd const& in,
139  Eigen::Matrix3Xd const& out,
140  Eigen::Affine3d* result);
141 } // namespace sparse_mapping
142 
143 #endif // SPARSE_MAPPING_REPROJECTION_H_
cv::Point2d
Point_< double > Point2d
Definition: reprojection.h:39
cv::Point_
Definition: reprojection.h:37
sparse_mapping::SelectRandomObservations
void SelectRandomObservations(const std::vector< Eigen::Vector3d > &all_landmarks, const std::vector< Eigen::Vector2d > &all_observations, size_t num_selected, std::vector< cv::Point3d > *landmarks, std::vector< cv::Point2d > *observations)
Definition: reprojection.cc:296
cv::Point3_
Definition: reprojection.h:39
camera
Definition: camera_model.h:26
sparse_mapping
Definition: localization_parameters.h:22
sparse_mapping::BundleAdjust
void BundleAdjust(std::vector< std::map< int, int > > const &pid_to_cid_fid, std::vector< Eigen::Matrix2Xd > const &cid_to_keypoint_map, double focal_length, std::vector< Eigen::Affine3d > *cid_to_cam_t_global, std::vector< Eigen::Vector3d > *pid_to_xyz, std::vector< std::map< int, int > > const &user_pid_to_cid_fid, std::vector< Eigen::Matrix2Xd > const &user_cid_to_keypoint_map, std::vector< Eigen::Vector3d > *user_pid_to_xyz, ceres::LossFunction *loss, ceres::Solver::Options const &options, ceres::Solver::Summary *summary, int first=0, int last=std::numeric_limits< int >::max(), bool fix_cameras=false, std::set< int > const &fixed_cameras=std::set< int >())
Definition: reprojection.cc:96
sparse_mapping::CountInliers
size_t CountInliers(const std::vector< Eigen::Vector3d > &landmarks, const std::vector< Eigen::Vector2d > &observations, const camera::CameraModel &camera, int tolerance, std::vector< size_t > *inliers)
Definition: reprojection.cc:333
camera::CameraModel
Definition: camera_model.h:31
sparse_mapping::GetLossFunction
ceres::LossFunction * GetLossFunction(std::string cost_fun, double th)
Definition: reprojection.cc:39
sparse_mapping::EstimateCamera
void EstimateCamera(camera::CameraModel *camera_estimate, std::vector< Eigen::Vector3d > *landmarks, const std::vector< Eigen::Vector2d > &observations, const ceres::Solver::Options &options, ceres::Solver::Summary *summary)
Definition: reprojection.cc:251
sparse_mapping::RandomInt
int RandomInt(int min, int max)
Definition: reprojection.cc:290
eigen_vectors.h
optimization_common::Affine3d
Eigen::Affine3d Affine3d(const Eigen::Matrix< double, 7, 1 > &affine_vector)
Definition: utilities.cc:43
sparse_mapping::BundleAdjustSmallSet
void BundleAdjustSmallSet(std::vector< Eigen::Matrix2Xd > const &features_n, double focal_length, std::vector< Eigen::Affine3d > *cam_t_global_n, Eigen::Matrix3Xd *pid_to_xyz, ceres::LossFunction *loss, ceres::Solver::Options const &options, ceres::Solver::Summary *summary)
Definition: reprojection.cc:200
cv
Definition: camera_params.h:31
sparse_mapping::RansacEstimateCamera
int RansacEstimateCamera(const std::vector< Eigen::Vector3d > &landmarks, const std::vector< Eigen::Vector2d > &observations, int num_tries, int inlier_tolerance, camera::CameraModel *camera_estimate, std::vector< Eigen::Vector3d > *inlier_landmarks_out=NULL, std::vector< Eigen::Vector2d > *inlier_observations_out=NULL, bool verbose=false)
Definition: reprojection.cc:355
cv::Point3d
Point3_< double > Point3d
Definition: reprojection.h:41
sparse_mapping::Find3DAffineTransform
void Find3DAffineTransform(Eigen::Matrix3Xd const &in, Eigen::Matrix3Xd const &out, Eigen::Affine3d *result)
Definition: reprojection.cc:459