Skip to content

Commit

Permalink
Remove unnecessary std::endl in log statements
Browse files Browse the repository at this point in the history
  • Loading branch information
ahojnnes committed Jul 24, 2024
1 parent 0a6e3d8 commit 73c8aab
Show file tree
Hide file tree
Showing 17 changed files with 85 additions and 93 deletions.
13 changes: 6 additions & 7 deletions glomap/controllers/global_mapper.cc
Original file line number Diff line number Diff line change
Expand Up @@ -184,7 +184,7 @@ bool GlobalMapper::Solve(const colmap::Database& database,
}
LOG(INFO) << "Global bundle adjustment iteration " << ite + 1 << " / "
<< options_.num_iteration_bundle_adjustment
<< ", stage 1 finished" << std::endl;
<< ", stage 1 finished (position only)";
run_timer.PrintSeconds();

// 6.2. Second stage: optimize rotations if desired
Expand All @@ -196,13 +196,13 @@ bool GlobalMapper::Solve(const colmap::Database& database,
}
LOG(INFO) << "Global bundle adjustment iteration " << ite + 1 << " / "
<< options_.num_iteration_bundle_adjustment
<< ", stage 2 finished" << std::endl;
<< ", stage 2 finished";
if (ite != options_.num_iteration_bundle_adjustment - 1)
run_timer.PrintSeconds();

// 6.3. Filter tracks based on the estatimation
UndistortImages(cameras, images, true);
LOG(INFO) << "Filtering tracks by reprojection ..." << std::endl;
LOG(INFO) << "Filtering tracks by reprojection ...";

bool status = true;
size_t filtere_num = 0;
Expand All @@ -221,8 +221,7 @@ bool GlobalMapper::Solve(const colmap::Database& database,
ite++;
}
if (status) {
LOG(INFO) << "fewer than 0.1% tracks are filtered, stop the iteration."
<< std::endl;
LOG(INFO) << "fewer than 0.1% tracks are filtered, stop the iteration.";
break;
}
}
Expand Down Expand Up @@ -251,7 +250,7 @@ bool GlobalMapper::Solve(const colmap::Database& database,

// Filter tracks based on the estatimation
UndistortImages(cameras, images, true);
LOG(INFO) << "Filtering tracks by reprojection ..." << std::endl;
LOG(INFO) << "Filtering tracks by reprojection ...";
TrackFilter::FilterTracksByReprojection(
view_graph,
cameras,
Expand All @@ -276,7 +275,7 @@ bool GlobalMapper::Solve(const colmap::Database& database,

// Filter tracks based on the estatimation
UndistortImages(cameras, images, true);
LOG(INFO) << "Filtering tracks by reprojection ..." << std::endl;
LOG(INFO) << "Filtering tracks by reprojection ...";
TrackFilter::FilterTracksByReprojection(
view_graph,
cameras,
Expand Down
5 changes: 2 additions & 3 deletions glomap/controllers/option_manager.cc
Original file line number Diff line number Diff line change
Expand Up @@ -269,12 +269,11 @@ void OptionManager::Parse(const int argc, char** argv) {
vmap.notify();

} catch (std::exception& exc) {
LOG(ERROR) << "Failed to parse options - " << exc.what() << "."
<< std::endl;
LOG(ERROR) << "Failed to parse options - " << exc.what() << ".";
// NOLINTNEXTLINE(concurrency-mt-unsafe)
exit(EXIT_FAILURE);
} catch (...) {
LOG(ERROR) << "Failed to parse options for unknown reason." << std::endl;
LOG(ERROR) << "Failed to parse options for unknown reason.";
// NOLINTNEXTLINE(concurrency-mt-unsafe)
exit(EXIT_FAILURE);
}
Expand Down
2 changes: 1 addition & 1 deletion glomap/controllers/option_manager.h
Original file line number Diff line number Diff line change
Expand Up @@ -142,7 +142,7 @@ void OptionManager::RegisterOption(const std::string& name, const T* option) {
options_string_.emplace_back(name,
reinterpret_cast<const std::string*>(option));
} else {
LOG(ERROR) << "Unsupported option type: " << name << std::endl;
LOG(ERROR) << "Unsupported option type: " << name;
}
}

Expand Down
21 changes: 14 additions & 7 deletions glomap/controllers/track_establishment.cc
Original file line number Diff line number Diff line change
Expand Up @@ -21,8 +21,11 @@ void TrackEngine::BlindConcatenation() {
// correspondences
image_pair_t counter = 0;
for (auto pair : view_graph_.image_pairs) {
std::cout << "\r Initializing pairs " << counter + 1 << " / "
<< view_graph_.image_pairs.size() << std::flush;
if ((++counter + 1) % 1000 == 0 ||
counter == view_graph_.image_pairs.size() - 1) {
std::cout << "\r Initializing pairs " << counter + 1 << " / "
<< view_graph_.image_pairs.size() << std::flush;
}
counter++;

const ImagePair& image_pair = pair.second;
Expand Down Expand Up @@ -66,8 +69,11 @@ void TrackEngine::TrackCollection(std::unordered_map<track_t, Track>& tracks) {
// Create tracks from the connected components of the point correspondences
size_t counter = 0;
for (auto pair : view_graph_.image_pairs) {
std::cout << "\r Establishing pairs " << counter + 1 << " / "
<< view_graph_.image_pairs.size() << std::flush;
if ((counter + 1) % 1000 == 0 ||
counter == view_graph_.image_pairs.size() - 1) {
std::cout << "\r Establishing pairs " << counter + 1 << " / "
<< view_graph_.image_pairs.size() << std::flush;
}
counter++;

const ImagePair& image_pair = pair.second;
Expand Down Expand Up @@ -105,10 +111,12 @@ void TrackEngine::TrackCollection(std::unordered_map<track_t, Track>& tracks) {
counter = 0;
size_t discarded_counter = 0;
for (auto& [track_id, correspondence_set] : track_map) {
if ((counter + 1) % 1000 == 0 || counter == track_map.size() - 1)
if ((counter + 1) % 1000 == 0 || counter == track_map.size() - 1) {
std::cout << "\r Establishing tracks " << counter + 1 << " / "
<< track_map.size() << std::flush;
}
counter++;

std::unordered_map<image_t, std::vector<Eigen::Vector2d>> image_id_set;
for (auto point_global_id : correspondence_set) {
// image_id is the higher 32 bits and feature_id is the lower 32 bits
Expand Down Expand Up @@ -137,9 +145,8 @@ void TrackEngine::TrackCollection(std::unordered_map<track_t, Track>& tracks) {
}
}

std::cout << std::endl;
LOG(INFO) << "Discarded " << discarded_counter
<< " tracks due to inconsistency" << std::endl;
<< " tracks due to inconsistency";
}

size_t TrackEngine::FindTracksForProblem(
Expand Down
8 changes: 4 additions & 4 deletions glomap/estimators/bundle_adjustment.cc
Original file line number Diff line number Diff line change
Expand Up @@ -11,11 +11,11 @@ bool BundleAdjuster::Solve(const ViewGraph& view_graph,
std::unordered_map<track_t, Track>& tracks) {
// Check if the input data is valid
if (images.empty()) {
std::cerr << "Number of images = " << images.size() << std::endl;
LOG(ERROR) << "Number of images = " << images.size();
return false;
}
if (tracks.empty()) {
std::cerr << "Number of tracks = " << tracks.size() << std::endl;
LOG(ERROR) << "Number of tracks = " << tracks.size();
return false;
}

Expand Down Expand Up @@ -44,7 +44,7 @@ bool BundleAdjuster::Solve(const ViewGraph& view_graph,
if (options_.verbose)
LOG(INFO) << summary.FullReport();
else
LOG(INFO) << summary.BriefReport() << std::endl;
LOG(INFO) << summary.BriefReport();

return summary.IsSolutionUsable();
}
Expand Down Expand Up @@ -101,7 +101,7 @@ void BundleAdjuster::AddPointToCameraConstraints(
image.features[observation.second]);
break;
default:
LOG(ERROR) << "Camera model not supported" << std::endl;
LOG(ERROR) << "Camera model not supported";
break;
}

Expand Down
25 changes: 12 additions & 13 deletions glomap/estimators/global_positioning.cc
Original file line number Diff line number Diff line change
Expand Up @@ -26,21 +26,22 @@ bool GlobalPositioner::Solve(const ViewGraph& view_graph,
std::unordered_map<image_t, Image>& images,
std::unordered_map<track_t, Track>& tracks) {
if (images.empty()) {
LOG(ERROR) << "Number of images = " << images.size() << std::endl;
LOG(ERROR) << "Number of images = " << images.size();
return false;
}
if (view_graph.image_pairs.empty() &&
options_.constraint_type != GlobalPositionerOptions::ONLY_POINTS) {
LOG(ERROR) << "Number of image_pairs = " << view_graph.image_pairs.size()
<< std::endl;
LOG(ERROR) << "Number of image_pairs = " << view_graph.image_pairs.size();
return false;
}
if (tracks.empty() &&
options_.constraint_type != GlobalPositionerOptions::ONLY_CAMERAS) {
LOG(ERROR) << "Number of tracks = " << tracks.size() << std::endl;
LOG(ERROR) << "Number of tracks = " << tracks.size();
return false;
}

LOG(INFO) << "Setting up the global positioner problem";

// Initialize the problem
Reset();

Expand All @@ -64,14 +65,16 @@ bool GlobalPositioner::Solve(const ViewGraph& view_graph,
// constant if desired
ParameterizeVariables(images, tracks);

LOG(INFO) << "Solving the global positioner problem";

ceres::Solver::Summary summary;
options_.solver_options.minimizer_progress_to_stdout = options_.verbose;
ceres::Solve(options_.solver_options, problem_.get(), &summary);

if (options_.verbose) {
LOG(INFO) << summary.FullReport();
} else {
LOG(INFO) << summary.BriefReport() << std::endl;
LOG(INFO) << summary.BriefReport();
}

ConvertResults(images);
Expand Down Expand Up @@ -128,8 +131,7 @@ void GlobalPositioner::InitializeRandomPositions(
}

if (options_.verbose)
LOG(INFO) << "Constrained positions: " << constrained_positions.size()
<< std::endl;
LOG(INFO) << "Constrained positions: " << constrained_positions.size();
}

void GlobalPositioner::AddCameraToCameraConstraints(
Expand Down Expand Up @@ -163,8 +165,7 @@ void GlobalPositioner::AddCameraToCameraConstraints(
if (options_.verbose)
LOG(INFO) << problem_->NumResidualBlocks()
<< " camera to camera constraints were added to the position "
"estimation problem."
<< std::endl;
"estimation problem.";
}

void GlobalPositioner::AddPointToCameraConstraints(
Expand All @@ -180,8 +181,7 @@ void GlobalPositioner::AddPointToCameraConstraints(
if (options_.verbose)
LOG(INFO) << num_pt_to_cam
<< " point to camera constriants were added to the position "
"estimation problem."
<< std::endl;
"estimation problem.";

if (num_pt_to_cam == 0) return;

Expand All @@ -196,8 +196,7 @@ void GlobalPositioner::AddPointToCameraConstraints(
static_cast<double>(num_pt_to_cam);
}
if (options_.verbose)
LOG(INFO) << "Point to camera weight scaled: " << weight_scale_pt
<< std::endl;
LOG(INFO) << "Point to camera weight scaled: " << weight_scale_pt;

if (loss_function_ptcam_uncalibrated_ == nullptr) {
loss_function_ptcam_uncalibrated_ =
Expand Down
29 changes: 12 additions & 17 deletions glomap/estimators/global_rotation_averaging.cc
Original file line number Diff line number Diff line change
Expand Up @@ -102,7 +102,7 @@ void RotationEstimator::SetupLinearSystem(

if (options_.verbose)
LOG(INFO) << "num_img: " << image_id_to_idx_.size()
<< ", num_dof: " << num_dof << std::endl;
<< ", num_dof: " << num_dof;

rotation_estimated_.conservativeResize(num_dof);

Expand Down Expand Up @@ -228,20 +228,19 @@ bool RotationEstimator::SolveL1Regression(
double curr_norm = 0;

ComputeResiduals(view_graph, images);
if (options_.verbose) LOG(INFO) << "ComputeResiduals done " << std::endl;
if (options_.verbose) LOG(INFO) << "ComputeResiduals done ";

int iteration = 0;
for (iteration = 0; iteration < options_.max_num_l1_iterations; iteration++) {
if (options_.verbose)
LOG(INFO) << "L1 ADMM iteration: " << iteration << std::endl;
if (options_.verbose) LOG(INFO) << "L1 ADMM iteration: " << iteration;

last_norm = curr_norm;
// use the current residual as b (Ax - b)

tangent_space_step_.setZero();
l1_solver.Solve(tangent_space_residual_, &tangent_space_step_);
if (tangent_space_step_.array().isNaN().sum() > 0) {
LOG(ERROR) << "nan error" << std::endl;
LOG(ERROR) << "nan error";
iteration++;
return false;
}
Expand All @@ -252,8 +251,7 @@ bool RotationEstimator::SolveL1Regression(
tangent_space_residual_)
.array()
.abs()
.sum()
<< std::endl;
.sum();

curr_norm = tangent_space_step_.norm();
UpdateGlobalRotations(view_graph, images);
Expand All @@ -265,15 +263,14 @@ bool RotationEstimator::SolveL1Regression(
options_.l1_step_convergence_threshold ||
std::abs(last_norm - curr_norm) < EPS) {
if (std::abs(last_norm - curr_norm) < EPS)
LOG(INFO) << "std::abs(last_norm - curr_norm) < EPS" << std::endl;
LOG(INFO) << "std::abs(last_norm - curr_norm) < EPS";
iteration++;
break;
}
opt_l1_solver.max_num_iterations =
std::min(opt_l1_solver.max_num_iterations * 2, 100);
}
if (options_.verbose)
LOG(INFO) << "L1 ADMM total iteration: " << iteration << std::endl;
if (options_.verbose) LOG(INFO) << "L1 ADMM total iteration: " << iteration;
return true;
}

Expand All @@ -290,7 +287,7 @@ bool RotationEstimator::SolveIRLS(const ViewGraph& view_graph,

const double sigma = DegToRad(options_.irls_loss_parameter_sigma);
if (options_.verbose)
LOG(INFO) << "sigma: " << options_.irls_loss_parameter_sigma << std::endl;
LOG(INFO) << "sigma: " << options_.irls_loss_parameter_sigma;

Eigen::ArrayXd weights_irls(sparse_matrix_.rows());
Eigen::SparseMatrix<double> at_weight;
Expand All @@ -304,8 +301,7 @@ bool RotationEstimator::SolveIRLS(const ViewGraph& view_graph,
int iteration = 0;
for (iteration = 0; iteration < options_.max_num_irls_iterations;
iteration++) {
if (options_.verbose)
LOG(INFO) << "IRLS iteration: " << iteration << std::endl;
if (options_.verbose) LOG(INFO) << "IRLS iteration: " << iteration;

// Compute the weights for IRLS
for (auto& [pair_id, pair_info] : rel_temp_info_) {
Expand All @@ -326,11 +322,11 @@ bool RotationEstimator::SolveIRLS(const ViewGraph& view_graph,
double tmp = err_squared + sigma * sigma;
w = sigma * sigma / (tmp * tmp);
} else if (options_.weight_type == RotationEstimatorOptions::HALF_NORM) {
LOG(ERROR) << "NOT IMPLEMENTED!!!" << std::endl;
LOG(ERROR) << "NOT IMPLEMENTED!!!";
}

if (std::isnan(w)) {
LOG(ERROR) << "nan weight!" << std::endl;
LOG(ERROR) << "nan weight!";
return false;
}

Expand Down Expand Up @@ -359,8 +355,7 @@ bool RotationEstimator::SolveIRLS(const ViewGraph& view_graph,
break;
}
}
if (options_.verbose)
LOG(INFO) << "IRLS total iteration: " << iteration << std::endl;
if (options_.verbose) LOG(INFO) << "IRLS total iteration: " << iteration;

return true;
}
Expand Down
4 changes: 2 additions & 2 deletions glomap/estimators/relpose_estimation.cc
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@ void EstimateRelativePoses(ViewGraph& view_graph,

image_pair_t inverval = std::ceil(image_pair_ids.size() / 10.);
LOG(INFO) << "Estimating relative pose for " << image_pair_ids.size()
<< " pairs" << std::endl;
<< " pairs";
for (image_pair_t chunks = 0; chunks < 10; chunks++) {
std::cout << "\r Estimating relative pose: " << chunks * 10 << "%"
<< std::flush;
Expand Down Expand Up @@ -65,7 +65,7 @@ void EstimateRelativePoses(ViewGraph& view_graph,
}
}
std::cout << "\r Estimating relative pose: 100%" << std::endl;
LOG(INFO) << "Estimating relative pose done" << std::endl;
LOG(INFO) << "Estimating relative pose done";
}

} // namespace glomap
Loading

0 comments on commit 73c8aab

Please sign in to comment.