From 1de99470f86a0a3a7c6d76127905f5e841c6376e Mon Sep 17 00:00:00 2001 From: Ryan Soussan Date: Sun, 21 Jul 2024 23:31:30 -0700 Subject: [PATCH] updated headers --- .../sparse_mapping/include/sparse_mapping/reprojection.h | 3 ++- .../sparse_mapping/include/sparse_mapping/sparse_mapping.h | 3 ++- localization/sparse_mapping/include/sparse_mapping/tensor.h | 3 ++- 3 files changed, 6 insertions(+), 3 deletions(-) diff --git a/localization/sparse_mapping/include/sparse_mapping/reprojection.h b/localization/sparse_mapping/include/sparse_mapping/reprojection.h index 3382ff9d98..379f9994e3 100644 --- a/localization/sparse_mapping/include/sparse_mapping/reprojection.h +++ b/localization/sparse_mapping/include/sparse_mapping/reprojection.h @@ -60,7 +60,8 @@ namespace sparse_mapping { **/ void BundleAdjust(std::vector > const& pid_to_cid_fid, std::vector const& cid_to_keypoint_map, - double focal_length, +std::vector const& cid_to_camera_id, + std::vector const& camera_id_to_camera_params, std::vector * cid_to_cam_t_global, std::vector * pid_to_xyz, std::vector > const& user_pid_to_cid_fid, diff --git a/localization/sparse_mapping/include/sparse_mapping/sparse_mapping.h b/localization/sparse_mapping/include/sparse_mapping/sparse_mapping.h index c9ec62ae19..fb9fbfd26d 100644 --- a/localization/sparse_mapping/include/sparse_mapping/sparse_mapping.h +++ b/localization/sparse_mapping/include/sparse_mapping/sparse_mapping.h @@ -180,7 +180,8 @@ double ComputeRaysAngle(int pid, std::vector > const& pid_to_ std::vector const& cam_ctrs, std::vector const& pid_to_xyz); // Filter points by reprojection error and other criteria -void FilterPID(double reproj_thresh, camera::CameraParameters const& camera_params, +void FilterPID(double reproj_thresh, std::vector const& camera_id_to_camera_params, + std::vector const& cid_to_cam_t_global, std::vector const& cid_to_cam_t_global, std::vector const& cid_to_keypoint_map, std::vector >* pid_to_cid_fid, std::vector* pid_to_xyz, diff --git a/localization/sparse_mapping/include/sparse_mapping/tensor.h b/localization/sparse_mapping/include/sparse_mapping/tensor.h index e72cfc60ef..58381fbaa2 100644 --- a/localization/sparse_mapping/include/sparse_mapping/tensor.h +++ b/localization/sparse_mapping/include/sparse_mapping/tensor.h @@ -176,7 +176,8 @@ namespace sparse_mapping { // Triangulates all points given camera positions. This is better // than what is in sparse map as it uses multiple view information. - void Triangulate(bool rm_invalid_xyz, double focal_length, + void Triangulate(bool rm_invalid_xyz, std::vector const& cid_to_camera_id, + std::vector const& camera_id_to_camera_params, std::vector const& cid_to_cam_t_global, std::vector const& cid_to_keypoint_map, std::vector > * pid_to_cid_fid,