Skip to content

Commit

Permalink
Merge pull request #24 from urbste/feature/revise_lo_ransac_optim
Browse files Browse the repository at this point in the history
Feature/revise lo ransac optim
  • Loading branch information
urbste authored Oct 18, 2023
2 parents f90562f + 2236069 commit a168b16
Show file tree
Hide file tree
Showing 26 changed files with 1,104 additions and 43 deletions.
3 changes: 3 additions & 0 deletions include/theia/theia.h
Original file line number Diff line number Diff line change
Expand Up @@ -104,6 +104,7 @@
#include "theia/math/matrix/sparse_cholesky_llt.h"
#include "theia/math/matrix/sparse_matrix.h"
#include "theia/math/matrix/spectra_linear_operator.h"
#include "theia/math/nullspace.h"
#include "theia/math/polynomial.h"
#include "theia/math/probability/sequential_probability_ratio.h"
#include "theia/math/qp_solver.h"
Expand All @@ -121,9 +122,11 @@
#include "theia/sfm/bundle_adjustment/bundle_adjuster.h"
#include "theia/sfm/bundle_adjustment/bundle_adjustment.h"
#include "theia/sfm/bundle_adjustment/create_loss_function.h"
#include "theia/sfm/bundle_adjustment/loss_functions.h"
#include "theia/sfm/bundle_adjustment/optimize_relative_position_with_known_rotation.h"
#include "theia/sfm/bundle_adjustment/orthogonal_vector_error.h"
#include "theia/sfm/bundle_adjustment/sampson_error.h"
#include "theia/sfm/bundle_adjustment/homography_error.h"
#include "theia/sfm/bundle_adjustment/position_error.h"
#include "theia/sfm/bundle_adjustment/gravity_error.h"
#include "theia/sfm/bundle_adjustment/fundamental_matrix_parameterization.h"
Expand Down
6 changes: 3 additions & 3 deletions pyexamples/sfm_pipeline_nerfstudio_poster.py
Original file line number Diff line number Diff line change
Expand Up @@ -14,7 +14,7 @@
from tqdm import tqdm
from utils import reprojection_error, plot_loftr_matches

min_num_inlier_matches = 30
min_num_inlier_matches = 50

# create correspondences of keypoints locations from indexed feature matches
def correspondence_from_indexed_matches(pts1, pts2):
Expand Down Expand Up @@ -99,12 +99,12 @@ def match_image_pair(img_i_data, img_j_data, matcher, min_conf, cam_prior0, cam_
parser = argparse.ArgumentParser(description='Argument parser for sfm pipeline')
parser.add_argument('--path_poster_images', type=str, default="/home/steffen/Data/nerfstudio/poster/images")
parser.add_argument('--output_path', type=str, default="/home/steffen/Data/nerfstudio/poster/pytheia/")
parser.add_argument('--reconstruction', type=str, default='global',
parser.add_argument('--reconstruction', type=str, default='incremental',
help='reconstruction type: global, incremental or hybrid')
parser.add_argument('--img_ext', default='png')
parser.add_argument('--device', default="cuda")
parser.add_argument('--use_fp16', default=True)
parser.add_argument('--temporal_match_window', default=4)
parser.add_argument('--temporal_match_window', default=6)

args = parser.parse_args()
reconstructiontype = args.reconstruction
Expand Down
2 changes: 1 addition & 1 deletion setup.py
Original file line number Diff line number Diff line change
Expand Up @@ -65,7 +65,7 @@ def create_package():

setuptools.setup(
name='pytheia',
version='0.1.26',
version='0.2.0',
description='A performant Structure from Motion library for Python',
long_description=open('README.md').read(),
long_description_content_type='text/markdown',
Expand Down
14 changes: 9 additions & 5 deletions src/theia/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -106,6 +106,7 @@ set(THEIA_SRC
sfm/bundle_adjustment/bundle_adjuster.cc
sfm/bundle_adjustment/bundle_adjustment.cc
sfm/bundle_adjustment/create_loss_function.cc
sfm/bundle_adjustment/loss_functions.cc
sfm/bundle_adjustment/optimize_relative_position_with_known_rotation.cc
sfm/camera/camera_intrinsics_model.cc
sfm/camera/camera.cc
Expand Down Expand Up @@ -181,6 +182,8 @@ set(THEIA_SRC
sfm/pose/four_point_homography.cc
sfm/pose/four_point_relative_pose_partial_rotation.cc
sfm/pose/fundamental_matrix_util.cc
sfm/pose/mlpnp.cc
sfm/pose/mlpnp_helper.cc
sfm/pose/orthographic_four_point.cc
sfm/pose/perspective_three_point.cc
sfm/pose/position_from_two_rays.cc
Expand Down Expand Up @@ -359,11 +362,11 @@ if (BUILD_TESTING)
# gtest(sfm/global_pose_estimation/compute_triplet_baseline_ratios)
# gtest(sfm/global_pose_estimation/hybrid_rotation_estimator)
# gtest(sfm/global_pose_estimation/lagrange_dual_rotation_estimator)
gtest(sfm/global_pose_estimation/least_unsquared_deviation_position_estimator)
gtest(sfm/global_pose_estimation/LiGT_position_estimator)
gtest(sfm/global_pose_estimation/linear_position_estimator)
gtest(sfm/global_pose_estimation/linear_rotation_estimator)
gtest(sfm/global_pose_estimation/nonlinear_position_estimator)
# gtest(sfm/global_pose_estimation/least_unsquared_deviation_position_estimator)
# gtest(sfm/global_pose_estimation/LiGT_position_estimator)
# gtest(sfm/global_pose_estimation/linear_position_estimator)
# gtest(sfm/global_pose_estimation/linear_rotation_estimator)
# gtest(sfm/global_pose_estimation/nonlinear_position_estimator)
# gtest(sfm/global_pose_estimation/pairwise_rotation_error)
# gtest(sfm/global_pose_estimation/pairwise_translation_and_scale_error)
# gtest(sfm/global_pose_estimation/pairwise_translation_error)
Expand All @@ -384,6 +387,7 @@ if (BUILD_TESTING)
# gtest(sfm/pose/four_point_homography)
# gtest(sfm/pose/four_point_relative_pose_partial_rotation)
# gtest(sfm/pose/fundamental_matrix_util)
gtest(sfm/pose/mlpnp)
# gtest(sfm/pose/orthographic_four_point)
# gtest(sfm/pose/perspective_three_point)
# gtest(sfm/pose/position_from_two_rays)
Expand Down
133 changes: 133 additions & 0 deletions src/theia/math/nullspace.h
Original file line number Diff line number Diff line change
@@ -0,0 +1,133 @@
// Copyright (C) 2023 Steffen Urban
// All rights reserved.
//
// Redistribution and use in source and binary forms, with or without
// modification, are permitted provided that the following conditions are
// met:
//
// * Redistributions of source code must retain the above copyright
// notice, this list of conditions and the following disclaimer.
//
// * Redistributions in binary form must reproduce the above
// copyright notice, this list of conditions and the following
// disclaimer in the documentation and/or other materials provided
// with the distribution.
//
// * Neither the name of The Regents or University of California nor the
// names of its contributors may be used to endorse or promote products
// derived from this software without specific prior written permission.
//
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDERS OR CONTRIBUTORS BE
// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
// POSSIBILITY OF SUCH DAMAGE.
//
// Please contact the author of this library if you have any questions.
// Author: Steffen Urban ([email protected])

#include <Eigen/Core>

using namespace std;

namespace theia {

// see Förstner et al, PCV, page 521
// Js(x)
template <typename T>
void jacobian_3_vec(const Eigen::Matrix<T, 3, 1>& vec,
Eigen::Matrix<T, 3, 3>& jac) {
jac = (Eigen::Matrix<T, 3, 3>::Identity() -
(vec * vec.transpose()) / (vec.transpose() * vec)) /
vec.norm();
}

// have a look at
// W. Foerstner, PCV, Page 370
// and S.Urban, MLPnP paper
template <typename T>
void get_information_for_bearing(const T& variance,
const Eigen::Matrix<T, 3, 3>& inv_cam_mat,
const Eigen::Matrix<T, 3, 3>& bearing_jac,
const Eigen::Matrix<T, 3, 2>& bearing_ns,
Eigen::Matrix<T, 2, 2>& information) {
const Eigen::Matrix<T, 3, 3> Exx =
Eigen::Matrix<T, 3, 1>(variance, variance, 0).asDiagonal();
const Eigen::Matrix<T, 3, 3> proj_Exx =
inv_cam_mat * Exx * inv_cam_mat.transpose();
const Eigen::Matrix<T, 3, 3> Evv =
bearing_jac * proj_Exx * bearing_jac.transpose();
const Eigen::Matrix<T, 2, 2> Ers = bearing_ns.transpose() * Evv * bearing_ns;
information = Ers.inverse();
}

/**
* compute the nullspace of a 3-vector efficiently
* without QR see W.Foerstner PCV, Page 778, eq. A.120)
*
* @param vector Eigen::Matrix<T, 3, 1>
*
* @return nullspace 3x2
*/
template <typename T>
void nullS_3x2_templated(const Eigen::Matrix<T, 3, 1>& vector,
Eigen::Matrix<T, 3, 2>& nullspace) {
const T x_n = vector(2);
const Eigen::Matrix<T, 2, 1> x_0(vector(0), vector(1));
const Eigen::Matrix<T, 2, 2> I_2 = Eigen::Matrix<T, 2, 2>::Identity();

const Eigen::Matrix<T, 2, 2> outer_prod = x_0 * x_0.transpose();
if (x_n > T(0)) {
const Eigen::Matrix<T, 2, 2> tmp = I_2 - outer_prod / (T(1) + x_n);
nullspace.row(0) = tmp.row(0);
nullspace.row(1) = tmp.row(1);
nullspace.row(2) = -x_0.transpose();
} else {
const Eigen::Matrix<T, 2, 2> tmp = I_2 - outer_prod / (T(1) - x_n);
nullspace.row(0) = tmp.row(0);
nullspace.row(1) = tmp.row(1);
nullspace.row(2) = x_0.transpose();
}
}

/**
* compute the nullspace of a 4-vector efficiently
* without QR, see W.Foerstner PCV, Page 778, eq. A.120)
*
* @param vector Eigen::Matrix<T, 4, 1>
*
* @return nullspace 4x3
*/
template <typename T>
void nullS_3x4_templated(const Eigen::Matrix<T, 4, 1>& vector,
Eigen::Matrix<T, 4, 3>& nullspace) {
const T x_n = vector(3);
const Eigen::Matrix<T, 3, 1> x_0(vector(0), vector(1), vector(2));
const Eigen::Matrix<T, 3, 3> I_3 = Eigen::Matrix<T, 3, 3>::Identity();

const Eigen::Matrix<T, 3, 3> outer_prod = x_0 * x_0.transpose();
if (x_n > T(0))
{
const Eigen::Matrix<T, 3, 3> tmp = I_3 - outer_prod / (T(1) + x_n);
nullspace.row(0) = tmp.row(0);
nullspace.row(1) = tmp.row(1);
nullspace.row(2) = tmp.row(2);
nullspace.row(3) = -x_0.transpose();
}
else
{
const Eigen::Matrix<T, 3, 3> tmp = I_3 - outer_prod / (T(1) - x_n);
nullspace.row(0) = tmp.row(0);
nullspace.row(1) = tmp.row(1);
nullspace.row(2) = tmp.row(2);
nullspace.row(3) = x_0.transpose();
}
}

} // namespace theia
11 changes: 9 additions & 2 deletions src/theia/sfm/bundle_adjustment/angular_epipolar_error.h
Original file line number Diff line number Diff line change
Expand Up @@ -42,6 +42,11 @@

namespace theia {

// As it happens quite often that this function will return false
// due to large outliers in the features matches and a LO-Ransac optimizer
// I changed the return value to be always true and set the error to a large
// value. Hence, never use this function with TRIVIAL loss function,
// but add a robust loss to it!
struct AngularEpipolarError {
public:
AngularEpipolarError(const Eigen::Vector2d& feature1,
Expand All @@ -65,6 +70,7 @@ struct AngularEpipolarError {

// Compute values A and B (Eq. 11 in the paper).
Eigen::Map<const Eigen::Matrix<T, 3, 1> > translation_map(translation);

const Eigen::Matrix<T, 3, 3> translation_term =
Eigen::Matrix<T, 3, 3>::Identity() -
translation_map * translation_map.transpose();
Expand All @@ -76,9 +82,10 @@ struct AngularEpipolarError {
feature1.cross(rotation_matrix.transpose() * feature2));

// Ensure the square root is real.
const T sqrt_term = a * a / T(4.0) - b_sqrt * b_sqrt;
const T sqrt_term = (a * a) / T(4.0) - b_sqrt * b_sqrt;
if (sqrt_term < T(0.0)) {
return false;
angular_epipolar_error[0] = T(1000);
return true;
}

angular_epipolar_error[0] = a / T(2.0) - sqrt(sqrt_term);
Expand Down
72 changes: 66 additions & 6 deletions src/theia/sfm/bundle_adjustment/bundle_adjust_two_views.cc
Original file line number Diff line number Diff line change
Expand Up @@ -36,13 +36,15 @@

#include <Eigen/Core>
#include <ceres/ceres.h>
#include <ceres/sphere_manifold.h>
#include <vector>

#include "theia/matching/feature_correspondence.h"
#include "theia/sfm/bundle_adjustment/angular_epipolar_error.h"
#include "theia/sfm/bundle_adjustment/bundle_adjustment.h"
#include "theia/sfm/bundle_adjustment/unit_norm_three_vector_parameterization.h"
#include "theia/sfm/bundle_adjustment/fundamental_matrix_parameterization.h"
#include "theia/sfm/bundle_adjustment/homography_error.h"
#include "theia/sfm/bundle_adjustment/sampson_error.h"
#include "theia/sfm/camera/camera.h"
#include "theia/sfm/camera/create_reprojection_error_cost_function.h"
Expand Down Expand Up @@ -197,11 +199,11 @@ BundleAdjustmentSummary BundleAdjustTwoViewsAngular(

// Set problem options.
ceres::Problem::Options problem_options;

problem_options.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
ceres::Problem problem(problem_options);

// Set solver options.
ceres::Solver::Options solver_options;
ceres::Solver::Options solver_options;
SetSolverOptions(options, &solver_options);
// Allow Ceres to determine the ordering.
solver_options.linear_solver_ordering.reset();
Expand All @@ -210,16 +212,17 @@ BundleAdjustmentSummary BundleAdjustTwoViewsAngular(
const int kParameterBlockSize = 3;
problem.AddParameterBlock(info->rotation_2.data(), kParameterBlockSize);
// Add the position as a parameter block, ensuring that the norm is 1.
ceres::Manifold* position_parameterization = new ceres::
AutoDiffManifold<UnitNormThreeVectorParameterization, 3, 3>;
ceres::Manifold* position_parameterization = new ceres::SphereManifold<3>();
problem.AddParameterBlock(
info->position_2.data(), kParameterBlockSize, position_parameterization);

// Add all the epipolar constraints from feature matches.
std::unique_ptr<ceres::LossFunction> loss =
CreateLossFunction(options.loss_function_type, options.robust_loss_width);
for (const FeatureCorrespondence& match : correspondences) {
problem.AddResidualBlock(AngularEpipolarError::Create(
match.feature1.point_, match.feature2.point_),
NULL,
loss.get(),
info->rotation_2.data(),
info->position_2.data());
}
Expand Down Expand Up @@ -265,7 +268,6 @@ BundleAdjustmentSummary OptimizeFundamentalMatrix(
solver_options.linear_solver_ordering.reset();

// Add the fundamental matrix as a parameter block.

ceres::LocalParameterization* fundamental_parametrization = new ceres::
AutoDiffLocalParameterization<FundamentalMatrixParametrization, 9, 7>;
problem.AddParameterBlock(
Expand Down Expand Up @@ -297,4 +299,62 @@ BundleAdjustmentSummary OptimizeFundamentalMatrix(
return summary;
}

BundleAdjustmentSummary OptimizeHomography(
const BundleAdjustmentOptions& options,
const std::vector<FeatureCorrespondence>& correspondences,
Eigen::Matrix3d* homography) {
CHECK_NOTNULL(homography);

BundleAdjustmentSummary summary;

// Start setup timer.
Timer timer;

// Set problem options.
ceres::Problem::Options problem_options;
problem_options.loss_function_ownership = ceres::DO_NOT_TAKE_OWNERSHIP;
ceres::Problem problem(problem_options);

// Set solver options.
ceres::Solver::Options solver_options;
SetSolverOptions(options, &solver_options);
// Allow Ceres to determine the ordering.
solver_options.linear_solver_ordering.reset();

std::unique_ptr<ceres::LossFunction> loss =
CreateLossFunction(options.loss_function_type, options.robust_loss_width);
for (const FeatureCorrespondence& match : correspondences) {
auto* homography_symmetric_geometric_cost_function =
new HomographySymmetricGeometricCostFunctor(
match.feature1.point_, match.feature2.point_);

problem.AddResidualBlock(
new ceres::AutoDiffCostFunction<HomographySymmetricGeometricCostFunctor,
4, // num_residuals
9>(
homography_symmetric_geometric_cost_function),
loss.get(),
homography->data());
}

// End setup time.
summary.setup_time_in_seconds = timer.ElapsedTimeInSeconds();

// Solve the problem.
ceres::Solver::Summary solver_summary;
ceres::Solve(solver_options, &problem, &solver_summary);
LOG_IF(INFO, options.verbose) << solver_summary.FullReport();

// Set the BundleAdjustmentSummary.
summary.solve_time_in_seconds = solver_summary.total_time_in_seconds;
summary.initial_cost = solver_summary.initial_cost;
summary.final_cost = solver_summary.final_cost;

// This only indicates whether the optimization was successfully run and makes
// no guarantees on the quality or convergence.
summary.success = solver_summary.termination_type != ceres::FAILURE;
(*homography) /= (*homography)(2, 2);
return summary;

}
} // namespace theia
7 changes: 7 additions & 0 deletions src/theia/sfm/bundle_adjustment/bundle_adjust_two_views.h
Original file line number Diff line number Diff line change
Expand Up @@ -89,6 +89,13 @@ BundleAdjustmentSummary OptimizeFundamentalMatrix(
Eigen::Matrix3d* fundamental_matrix);


// Optimizes a homography matrix. It uses the manifold presented in
// ceres-solver/examples/libmv_homography.cc
BundleAdjustmentSummary OptimizeHomography(
const BundleAdjustmentOptions& options,
const std::vector<FeatureCorrespondence>& correspondences,
Eigen::Matrix3d* homography);

} // namespace theia

#endif // THEIA_SFM_BUNDLE_ADJUSTMENT_BUNDLE_ADJUST_TWO_VIEWS_H_
Loading

0 comments on commit a168b16

Please sign in to comment.