|
NASA Astrobee Robot Software
0.19.1
Flight software for the Astrobee robots operating inside the International Space Station.
|
Go to the documentation of this file.
18 #ifndef SPARSE_MAPPING_REPROJECTION_H_
19 #define SPARSE_MAPPING_REPROJECTION_H_
21 #include <Eigen/Geometry>
23 #include <ceres/ceres.h>
61 void BundleAdjust(std::vector<std::map<int, int> >
const& pid_to_cid_fid,
62 std::vector<Eigen::Matrix2Xd >
const& cid_to_keypoint_map,
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>());
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);
97 const std::vector<Eigen::Vector2d> & all_observations,
size_t num_selected,
98 std::vector<cv::Point3d> * landmarks, std::vector<cv::Point2d> * observations);
102 size_t CountInliers(
const std::vector<Eigen::Vector3d> & landmarks,
103 const std::vector<Eigen::Vector2d> & observations,
105 std::vector<size_t>* inliers);
117 const std::vector<Eigen::Vector2d> & observations,
118 const ceres::Solver::Options & options, ceres::Solver::Summary* summary);
130 const std::vector<Eigen::Vector2d> & observations,
132 std::vector<Eigen::Vector3d> * inlier_landmarks_out = NULL,
133 std::vector<Eigen::Vector2d> * inlier_observations_out = NULL,
134 bool verbose =
false);
139 Eigen::Matrix3Xd
const& out,
143 #endif // SPARSE_MAPPING_REPROJECTION_H_
Point_< double > Point2d
Definition: reprojection.h:39
Definition: reprojection.h:37
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
Definition: reprojection.h:39
Definition: camera_model.h:26
Definition: localization_parameters.h:22
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
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
Definition: camera_model.h:31
ceres::LossFunction * GetLossFunction(std::string cost_fun, double th)
Definition: reprojection.cc:39
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
int RandomInt(int min, int max)
Definition: reprojection.cc:290
Eigen::Affine3d Affine3d(const Eigen::Matrix< double, 7, 1 > &affine_vector)
Definition: utilities.cc:43
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
Definition: camera_params.h:31
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
Point3_< double > Point3d
Definition: reprojection.h:41
void Find3DAffineTransform(Eigen::Matrix3Xd const &in, Eigen::Matrix3Xd const &out, Eigen::Affine3d *result)
Definition: reprojection.cc:459