Skip to content

Commit

Permalink
formatting
Browse files Browse the repository at this point in the history
  • Loading branch information
rsoussan committed Jul 22, 2024
1 parent 1de9947 commit bce16c8
Show file tree
Hide file tree
Showing 3 changed files with 5 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,7 @@ namespace sparse_mapping {
**/
void BundleAdjust(std::vector<std::map<int, int> > const& pid_to_cid_fid,
std::vector<Eigen::Matrix2Xd > const& cid_to_keypoint_map,
std::vector<int> const& cid_to_camera_id,
std::vector<int> const& cid_to_camera_id,
std::vector<camera::CameraParameters> const& camera_id_to_camera_params,
std::vector<Eigen::Affine3d> * cid_to_cam_t_global,
std::vector<Eigen::Vector3d> * pid_to_xyz,
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -180,8 +180,8 @@ double ComputeRaysAngle(int pid, std::vector<std::map<int, int> > const& pid_to_
std::vector<Eigen::Vector3d> const& cam_ctrs, std::vector<Eigen::Vector3d> const& pid_to_xyz);

// Filter points by reprojection error and other criteria
void FilterPID(double reproj_thresh, std::vector<camera::CameraParameters> const& camera_id_to_camera_params,
std::vector<Eigen::Affine3d > const& cid_to_cam_t_global,
void FilterPID(double reproj_thresh, std::vector<int> const& cid_to_camera_id,
std::vector<camera::CameraParameters> const& camera_id_to_camera_params,
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,
Expand Down
4 changes: 2 additions & 2 deletions localization/sparse_mapping/include/sparse_mapping/tensor.h
Original file line number Diff line number Diff line change
Expand Up @@ -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<int> const& cid_to_camera_id,
std::vector<camera::CameraParameters> const& camera_id_to_camera_params,
void Triangulate(bool rm_invalid_xyz, std::vector<int> const& cid_to_camera_id,
std::vector<camera::CameraParameters> const& camera_id_to_camera_params,
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,
Expand Down

0 comments on commit bce16c8

Please sign in to comment.