|
| DEFINE_int32 (min_valid, 20, "Minimum number of valid inlier matches required to keep matches for given image pair.") |
|
| DEFINE_int32 (max_pairwise_matches, 5000, "Maximum number of matches to keep in any image pair.") |
|
| DEFINE_int32 (num_subsequent_images, std::numeric_limits< int32_t >::max()/2, "When no vocabulary tree is provided, match every image against this " "many subsequent images.") |
|
| DEFINE_int32 (match_all_rate, -1, "If nonnegative, match one of every match_all_rate images to every other image.") |
|
| DEFINE_bool (skip_filtering, false, "Skip filtering of outliers after bundle adjustment.") |
|
| DEFINE_bool (skip_adding_new_matches_on_merging, false, "When merging maps, do not take advantage of performed matching to add new tracks.") |
|
| DEFINE_bool (fast_merge, false, "When merging maps that have shared images, use those and skip doing additional matches among the images.") |
|
| DEFINE_double (reproj_thresh, 5.0, "Filter points with re-projection error higher than this.") |
|
| DEFINE_int32 (max_num_iterations, 1000, "Maximum number of iterations for bundle adjustment solver.") |
|
| DEFINE_int32 (num_ba_passes, 5, "How many times to run bundle adjustment, removing outliers each time.") |
|
| DEFINE_string (cost_function, "Cauchy", "Choose a bundle adjustment cost function from: Cauchy, PseudoHuber, Huber, L1, L2.") |
|
| DEFINE_double (cost_function_threshold, 2.0, "Threshold to use with some cost functions, e.g., Cauchy.") |
|
| DEFINE_int32 (first_ba_index, 0, "Vary only cameras starting with this index during bundle adjustment.") |
|
| DEFINE_int32 (last_ba_index, std::numeric_limits< int >::max(), "Vary only cameras ending with this index during bundle adjustment.") |
|
| DEFINE_bool (silent_matching, false, "Do not print a lot of verbose info when matching.") |
|
std::string | sparse_mapping::print_vec (double a) |
|
std::string | sparse_mapping::print_vec (Eigen::Vector3d a) |
|
int | sparse_mapping::ReadMatches (std::string const &matches_file, openMVG::matching::PairWiseMatches *match_map) |
|
void | sparse_mapping::WriteMatches (openMVG::matching::PairWiseMatches const &match_map, std::string const &matches_file) |
|
void | sparse_mapping::BuildMapPerformMatching (openMVG::matching::PairWiseMatches *match_map, std::vector< Eigen::Matrix2Xd > const &cid_to_keypoint_map, std::vector< cv::Mat > const &cid_to_descriptor_map, camera::CameraParameters const &camera_params, CIDPairAffineMap *relative_affines, std::mutex *match_mutex, int i, int j, bool compute_rays_angle, double *rays_angle) |
|
void | sparse_mapping::MatchFeatures (const std::string &essential_file, const std::string &matches_file, sparse_mapping::SparseMap *s) |
|
void | sparse_mapping::BuildTracks (bool rm_invalid_xyz, const std::string &matches_file, sparse_mapping::SparseMap *s) |
|
void | sparse_mapping::IncrementalBA (std::string const &essential_file, sparse_mapping::SparseMap *s) |
|
void | sparse_mapping::CloseLoop (sparse_mapping::SparseMap *s) |
|
void | sparse_mapping::BundleAdjust (bool fix_all_cameras, sparse_mapping::SparseMap *map, std::set< int > const &fixed_cameras=std::set< int >()) |
|
void | sparse_mapping::BundleAdjustment (sparse_mapping::SparseMap *s, ceres::LossFunction *loss, const ceres::Solver::Options &options, ceres::Solver::Summary *summary, int first=0, int last=std::numeric_limits< int >::max(), bool fix_all_cameras=false, std::set< int > const &fixed_cameras=std::set< int >()) |
|
void | sparse_mapping::AppendMapFile (std::string const &mapOut, std::string const &mapIn, int num_image_overlaps_at_endpoints, double outlier_factor, bool bundle_adjust, bool fix_first_map) |
|
double | sparse_mapping::estimateCloseDistance (std::vector< Eigen::Vector3d > const &vec) |
|
void | sparse_mapping::TransformTracks (std::map< int, int > const &cid2cid, bool rm_tracks_of_len_one, std::vector< std::map< int, int > > *pid_to_cid_fid) |
|
void | sparse_mapping::FindPidCorrespondences (std::vector< std::map< int, int > > const &A_cid_fid_to_pid, std::vector< std::map< int, int > > const &B_cid_fid_to_pid, std::vector< std::map< int, int > > const &C_pid_to_cid_fid, int num_acid, std::map< int, int > *A2B, std::map< int, int > *B2A) |
|
void | sparse_mapping::findMatchingTracks (sparse_mapping::SparseMap *A_in, sparse_mapping::SparseMap *B_in, sparse_mapping::SparseMap *C_out, std::string const &output_map, int num_image_overlaps_at_endpoints, std::map< int, int > &A2B, std::map< int, int > &B2A) |
|
void | sparse_mapping::findTracksForSharedImages (sparse_mapping::SparseMap *A_in, sparse_mapping::SparseMap *B_in, std::map< int, int > &A2B, std::map< int, int > &B2A) |
|
void | sparse_mapping::TransformMap (std::map< int, int > &cid2cid, sparse_mapping::SparseMap *C_out) |
|
void | sparse_mapping::MergeMaps (sparse_mapping::SparseMap *A_in, sparse_mapping::SparseMap *B_in, int num_image_overlaps_at_endpoints, double outlier_factor, std::string const &output_map, sparse_mapping::SparseMap *C_out) |
|
void | sparse_mapping::ExtractSubmap (std::vector< std::string > *keep_ptr, sparse_mapping::SparseMap *map_ptr) |
|
double | sparse_mapping::RegistrationOrVerification (std::vector< std::string > const &data_files, bool verification, sparse_mapping::SparseMap *s) |
|
void | sparse_mapping::PrintTrackStats (std::vector< std::map< int, int > >const &pid_to_cid_fid, std::string const &step) |
|
template<class IterT > |
void | sparse_mapping::WriteCIDPairAffineIterator (IterT it, IterT end, std::ofstream *file) |
|
template<class IterT > |
void | sparse_mapping::ReadAffine (std::ifstream *file, IterT output_iter) |
|
template<class IterT > |
void | sparse_mapping::PushBackCIDPairAffine (std::ifstream *file, IterT output_iter, IterT output_iter_end) |
|
template<class IterT > |
void | sparse_mapping::PushBackCIDPairAffine (std::ifstream *file, IterT iter) |
|
void | sparse_mapping::WriteAffineCSV (CIDPairAffineMap const &relative_affines, std::string const &output_filename) |
|
void | sparse_mapping::WriteAffineCSV (CIDAffineTupleVec const &relative_affines, std::string const &output_filename) |
|
void | sparse_mapping::ReadAffineCSV (std::string const &input_filename, CIDPairAffineMap *relative_affines) |
|
void | sparse_mapping::ReadAffineCSV (std::string const &input_filename, CIDAffineTupleVec *relative_affines) |
|
void | sparse_mapping::FindEssentialAndInliers (Eigen::Matrix2Xd const &keypoints1, Eigen::Matrix2Xd const &keypoints2, std::vector< cv::DMatch > const &matches, camera::CameraParameters const &camera_params, std::vector< cv::DMatch > *inlier_matches, std::vector< size_t > *vec_inliers, Eigen::Matrix3d *essential_matrix, const int ransac_iterations=4096) |
|
void | sparse_mapping::BuildMapFindEssentialAndInliers (const Eigen::Matrix2Xd &keypoints1, const Eigen::Matrix2Xd &keypoints2, const std::vector< cv::DMatch > &matches, camera::CameraParameters const &camera_params, bool compute_inliers_only, size_t cam_a_idx, size_t cam_b_idx, std::mutex *match_mutex, CIDPairAffineMap *relative_b_t_a, std::vector< cv::DMatch > *inlier_matches, bool compute_rays_angle, double *rays_angle) |
|
void | sparse_mapping::Triangulate (bool rm_invalid_xyz, double focal_length, std::vector< Eigen::Affine3d > const &cid_to_cam_t_global, std::vector< Eigen::Matrix2Xd > const &cid_to_keypoint_map, std::vector< std::map< int, int > > *pid_to_cid_fid, std::vector< Eigen::Vector3d > *pid_to_xyz, std::vector< std::map< int, int > > *cid_fid_to_pid) |
|