diff --git a/localization/sparse_mapping/include/sparse_mapping/reprojection.h b/localization/sparse_mapping/include/sparse_mapping/reprojection.h index 379f9994e3..5e0243c8f4 100644 --- a/localization/sparse_mapping/include/sparse_mapping/reprojection.h +++ b/localization/sparse_mapping/include/sparse_mapping/reprojection.h @@ -60,7 +60,7 @@ namespace sparse_mapping { **/ void BundleAdjust(std::vector > const& pid_to_cid_fid, std::vector const& cid_to_keypoint_map, -std::vector const& cid_to_camera_id, + 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, diff --git a/localization/sparse_mapping/include/sparse_mapping/sparse_mapping.h b/localization/sparse_mapping/include/sparse_mapping/sparse_mapping.h index fb9fbfd26d..1dfd3d2d00 100644 --- a/localization/sparse_mapping/include/sparse_mapping/sparse_mapping.h +++ b/localization/sparse_mapping/include/sparse_mapping/sparse_mapping.h @@ -180,8 +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, std::vector const& camera_id_to_camera_params, - std::vector const& cid_to_cam_t_global, +void FilterPID(double reproj_thresh, 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, 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 58381fbaa2..cf382361f5 100644 --- a/localization/sparse_mapping/include/sparse_mapping/tensor.h +++ b/localization/sparse_mapping/include/sparse_mapping/tensor.h @@ -176,8 +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, std::vector const& cid_to_camera_id, - std::vector const& camera_id_to_camera_params, + 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,