Skip to content

Commit

Permalink
Merge branch 'develop' of https://github.com/openMVG/openMVG into dev…
Browse files Browse the repository at this point in the history
…elop
  • Loading branch information
pmoulon committed Jul 18, 2018
2 parents 34330bb + 3e380e4 commit 025344f
Show file tree
Hide file tree
Showing 48 changed files with 3,193 additions and 503 deletions.
2 changes: 1 addition & 1 deletion BUILD.md
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ $ ./bootstrap-vcpkg.sh/bat

Checking OpenMVG 3rd party dependencies by using VCPKG (configure your build triplet if needed see `--triplet`)
```shell
$ ./vcpkg install cereal ceres eigen3 libjpeg-turbo libpng tiff
$ ./vcpkg install cereal ceres eigen3 libjpeg-turbo libpng tiff
```
Note: If you want to use ceres with a sparse back end, please use one of this choice `ceres[cxsparse]` or `ceres[suitesparse]` or `ceres[eigensparse]`.

Expand Down
2 changes: 1 addition & 1 deletion docs/sphinx/rst/dependencies/osi_clp.rst
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@ USAGE

openMVG uses the [OSI]_ and the [CLP]_ solver in order to solve linear programs [LP]_.

CLP has been choosen because it is known to support problems of up to 1.5 million constraints [CLP FAQ]_.
CLP has been chosen because it is known to support problems of up to 1.5 million constraints [CLP FAQ]_.

[LPSOLVE]_ has been tested but tests shown that it is less reliable (sometimes, there is no convergence to a solution).

Expand Down
13 changes: 6 additions & 7 deletions docs/sphinx/rst/openMVG/linear_programming/lp.rst
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ openMVG provide access to different solvers (not exhaustive):
- OSI_CLP (COIN-OR) project,
- MOSEK commercial, free in a research context.

Those solver have been choosen due to the stability of their results and ability to handle large problems without numerical stability (LPSolve and GPLK have been discarded after extensive experiments).
Those solver have been chosen due to the stability of their results and ability to handle large problems without numerical stability (LPSolve and GPLK have been discarded after extensive experiments).

I refer the reader to openMVG/src/openMVG/linearProgramming/linear_programming_test.cpp to know more.

Expand All @@ -65,14 +65,14 @@ The linear programming module of openMVG can be used for:
Here an example of usage of the framework:

.. code-block:: c++

// Setup the LP (fill A,b,c and the constraint over x)
LP_Constraints cstraint;
BuildLinearProblem(cstraint);

// Solve the LP with the solver of your choice
std::vector<double> vec_solution(2);
#if OPENMVG_HAVE_MOSEK
#if OPENMVG_HAVE_MOSEK
MOSEK_SolveWrapper solver(2);
#else
OSI_CLP_SolverWrapper solver(2);
Expand Down Expand Up @@ -109,7 +109,7 @@ Optimization of this upper bound parameter can be done by iterating over all the
Require: gammaLow, gammUp (Low and upper bound of the parameter to optimize)
Require: the LP problem (cstraintBuilder)
Ensure: the optimal gamma value, or return infeasibility of the contraints set.

BisectionLP(
LP_Solver & solver,
ConstraintBuilder & cstraintBuilder,
Expand All @@ -128,15 +128,15 @@ Optimization of this upper bound parameter can be done by iterating over all the
//-- Setup constraint and solver
cstraintBuilder.Build(gamma, constraint);
solver.setup( constraint );

//-- Solving
bool bFeasible = solver.solve();

//-- According feasibility update the corresponding bound
//-> Feasible, update the upper bound
//-> Not feasible, update the lower bound
(bFeasible) ? gammaUp = gamma; : gammaLow = gamma;

} while (k < maxIteration && gammaUp - gammaLow > eps);
}

Expand All @@ -162,4 +162,3 @@ OpenMVG propose solvers for the following problems:

- Translation averaging:
- Registration of relative translations to compute global translations [GlobalACSfM]_.

2 changes: 1 addition & 1 deletion docs/sphinx/rst/software/Geodesy/geodesy.rst
Original file line number Diff line number Diff line change
Expand Up @@ -141,7 +141,7 @@ Since MVS frameworks does not like large double values (raw GPS coordinates) you
Use-case: command line used for a flat UAV survey
====================================================

Launched on the dataset Swiss Quarry `Geotagged multispectral images <http://chuqavct.preview.infomaniak.com/postflight-examples/06-mining-quarry-switzerland/geotagged-images.zip>`_.
Launched on the dataset Swiss Quarry `Geotagged multispectral images <https://senseflycom.s3.amazonaws.com/datasets/quarry-switzerland/geotagged-images.zip>`_.

.. code-block:: c++

Expand Down
54 changes: 47 additions & 7 deletions docs/sphinx/rst/software/SfM/IncrementalSfM.rst
Original file line number Diff line number Diff line change
Expand Up @@ -37,12 +37,12 @@ Information and usage
The chain is designed to run on a sfm_data.json file and some pre-computed matches.

.. code-block:: c++

$ openMVG_main_IncrementalSfM -i Dataset/matches/sfm_data.json -m Dataset/matches/ -o Dataset/out_Incremental_Reconstruction/

openMVG_main_IncrementalSfM displays to you some initial pairs that share an important number of common point.
**Please select two image index that are convergent and the 3D reconstruction will start.
The initial pair must be choosen with numerous correspondences while keeping a wide enough baseline.**
The initial pair must be chosen with numerous correspondences while keeping a wide enough baseline.**

Arguments description:

Expand All @@ -55,7 +55,7 @@ Arguments description:
- **[-m|--matchdir]**

- path were geometric matches were stored

- **[-o|--outdir]**

- path where the output data will be stored
Expand All @@ -82,21 +82,61 @@ Arguments description:

- **[-f|--refineIntrinsics]**
User can control exactly which parameter will be considered as constant/variable and combine them by using the '|' operator.
- ADJUST_ALL -> refine all existing parameters (default)
- NONE -> intrinsic parameters are held as constant
- ADJUST_FOCAL_LENGTH -> refine only the focal length
- ADJUST_PRINCIPAL_POINT -> refine only the principal point position
- ADJUST_DISTORTION -> refine only the distortion coefficient(s) (if any)

- NOTE Options can be combined thanks to '|':
- ADJUST_FOCAL_LENGTH|ADJUST_PRINCIPAL_POINT
-> refine the focal length & the principal point position

- ADJUST_FOCAL_LENGTH|ADJUST_DISTORTION
-> refine the focal length & the distortion coefficient(s) (if any)

- ADJUST_PRINCIPAL_POINT|ADJUST_DISTORTION
-> refine the principal point position & the distortion coefficient(s) (if any)

*************************************
openMVG_main_IncrementalSfM2
*************************************

`openMVG_main_IncrementalSfM2` is a more generic incremental pipeline than `openMVG_main_IncrementalSfM` since it can:

- extend a scene that was started by using existing poses or an abstract scene initialization (2 view or n-views).

The main features are:

- The reconstruction initialization is done thanks to an abstract interface, `SfMSceneInitializer`.
- The triangulation stage considers the entire scene tracks.
- The resection stage is based on 2d-3D matching confidence.
- The reconstruction can start from existing camera poses.

This new engine (`SequentialSfMReconstructionEngine`) is easier to read and to customize than `SequentialSfMReconstructionEngine`.

- **fast**:

- Since it localizes images as soon as it can, fewer Bundle Adjustment steps are observed than in `SequentialSfMReconstructionEngine`.

- **flexible**:

- The engine can extend a partial reconstruction, you can call this engine on the results of any other SfM Engine. For example, you can run GlobalSfM (to obtain the pose of the camera triplets) and then run SequentialSfMReconstructionEngine2 to localize the remaining images.

- You can now initialize the reconstruction with a n-view reconstruction (Stellar [2]) and provide a very stable seed for the reconstruction.

For the moment three SfMSceneInitializer are implemented:

- `SfMSceneInitializer`:

- Keep the existing poses. -> extend a previous reconstruction.

- `SfMSceneInitializerMaxPair`:

- Initialize a 2-view reconstruction (the relative pose with the most of inliers).

- `SfMSceneInitializerStellar`:

- Initialize a stellar reconstruction (a n-view reconstruction with edge connected to a central unique pose: i.e a 5 pose stellar configuration could be defined by 4 relative pairs {{0,1}, {0,2}, {0,6}, {0,10}}.)
10 changes: 4 additions & 6 deletions docs/sphinx/rst/software/colorHarmonization/color.rst
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,7 @@ In a multiple-view image acquisition process, color consistency is not ensured.
This is an important problem for image fusion tasks: object texturing or mosaics blending for example.
In automatic mode, the camera adapts its settings --shutter-speed and aperture-- to the captured image content.
Therefore the color of objects changes over an image sequence.

.. figure:: globalMultipleViewColorConsistency_PRB.png
:align: center

Expand All @@ -21,14 +21,12 @@ This module propose an interface to solve this problem:
[Moulon13]_ propose a global multi-view color consistency solution that in a first step selects robustly the common color information between images and in a second step estimates the color transformations that set all pictures in a common color reference, which involves a global minimization.
It uses a compact histogram representation of the shared color information per image pairs and solve the color consistency by using a linear program with a gain and offset model for each image.

A reference have to be choosen in order to set the color reference.
A reference have to be chosen in order to set the color reference.

Here the obtained results on the image sequence after having choosen a "white" or "blue" image as reference:
Here the obtained results on the image sequence after having chosen a "white" or "blue" image as reference:

.. figure:: globalMultipleViewColorConsistency_solveA.png
:align: center

.. figure:: globalMultipleViewColorConsistency_solveB.png
:align: center


10 changes: 5 additions & 5 deletions src/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -369,13 +369,13 @@ endif()
# - only external and enabled only if OpenMVG_USE_OPENCV is set to ON
# ==============================================================================
if (OpenMVG_USE_OPENCV)
find_package( OpenCV 3.0 QUIET )
if (NOT OpenCV_FOUND)
message(STATUS "OpenCV was not found. Disabling OpenCV support.")
find_package( OpenCV QUIET )
if (NOT OpenCV_FOUND OR OpenCV_VERSION VERSION_LESS "3.0.0")
message(STATUS "OpenCV was not found (note that OpenCV version >= 3.0.0 is required). -> Disabling OpenCV support.")
UPDATE_CACHE_VARIABLE(OpenMVG_USE_OPENCV OFF)
UPDATE_CACHE_VARIABLE(OpenMVG_USE_OCVSIFT OFF)
endif (NOT OpenCV_FOUND)
endif (OpenMVG_USE_OPENCV)
endif()
endif()


# ==============================================================================
Expand Down
4 changes: 2 additions & 2 deletions src/openMVG/cameras/Camera_Spherical.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,7 @@ using class_type = Intrinsic_Spherical;
*/
virtual Vec2 cam2ima(const Vec2 &p) const override
{
const size_t size = std::max(w(), h());
const double size(std::max(w(), h()));
return {
p.x() * size + w() / 2.0,
p.y() * size + h() / 2.0 };
Expand All @@ -102,7 +102,7 @@ using class_type = Intrinsic_Spherical;
*/
virtual Vec2 ima2cam(const Vec2 &p) const override
{
const size_t size = std::max(w(), h());
const double size(std::max(w(), h()));
return {
(p.x() - w() / 2.0) / size,
(p.y() - h() / 2.0) / size };
Expand Down
2 changes: 0 additions & 2 deletions src/openMVG/features/feature.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -31,8 +31,6 @@ class PointFeature {
friend std::istream& operator>>(std::istream& in, PointFeature& obj);

public:
EIGEN_MAKE_ALIGNED_OPERATOR_NEW

PointFeature(float x=0.0f, float y=0.0f);

float x() const;
Expand Down
6 changes: 6 additions & 0 deletions src/openMVG/graph/graph_graphviz_export.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -17,6 +17,10 @@
#include <map>
#include <string>

#if __APPLE__
#include "TargetConditionals.h"
#endif

#include "openMVG/types.hpp"

namespace openMVG {
Expand Down Expand Up @@ -77,8 +81,10 @@ inline void exportToGraphvizData

//Use Graphviz
const std::string cmd = "neato -Tsvg -O -Goverlap=scale -Gsplines=false " + sfile;
#ifndef TARGET_OS_IPHONE
const int ret = std::system(cmd.c_str());
(void)ret;
#endif
}

} // namespace graph
Expand Down
1 change: 1 addition & 0 deletions src/openMVG/matching_image_collection/E_ACRobust.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
#include "openMVG/cameras/Camera_Pinhole.hpp"
#include "openMVG/matching/indMatch.hpp"
#include "openMVG/matching_image_collection/Geometric_Filter_utils.hpp"
#include "openMVG/multiview/solver_essential_five_point.hpp"
#include "openMVG/multiview/solver_essential_kernel.hpp"
#include "openMVG/multiview/essential.hpp"
#include "openMVG/robust_estimation/robust_estimator_ACRansac.hpp"
Expand Down
8 changes: 4 additions & 4 deletions src/openMVG/multiview/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -40,7 +40,7 @@ target_include_directories(openMVG_multiview
set_target_properties(openMVG_multiview PROPERTIES SOVERSION ${OPENMVG_VERSION_MAJOR} VERSION "${OPENMVG_VERSION_MAJOR}.${OPENMVG_VERSION_MINOR}")

add_library(openMVG_multiview_test_data ${MULTIVIEWTESTDATA})
target_link_libraries(openMVG_multiview_test_data PRIVATE openMVG_numeric)
target_link_libraries(openMVG_multiview_test_data PRIVATE openMVG_numeric openMVG_multiview)
set_property(TARGET openMVG_multiview_test_data PROPERTY FOLDER OpenMVG/OpenMVG)

# Triangulation routines
Expand All @@ -49,11 +49,11 @@ UNIT_TEST(openMVG triangulation_nview "openMVG_multiview_test_data;openMVG_multi

# Solvers
UNIT_TEST(openMVG solver_affine "openMVG_multiview")
UNIT_TEST(openMVG solver_fundamental_kernel "openMVG_multiview")
UNIT_TEST(openMVG solver_essential_kernel "openMVG_multiview_test_data;openMVG_multiview")
UNIT_TEST(openMVG solver_homography_kernel "openMVG_multiview_test_data;openMVG_multiview")
UNIT_TEST(openMVG solver_essential_eight_point "openMVG_multiview_test_data;openMVG_multiview")
UNIT_TEST(openMVG solver_essential_five_point "openMVG_multiview_test_data;openMVG_multiview")
UNIT_TEST(openMVG solver_essential_three_point "openMVG_multiview")
UNIT_TEST(openMVG solver_fundamental_kernel "openMVG_multiview")
UNIT_TEST(openMVG solver_homography_kernel "openMVG_multiview_test_data;openMVG_multiview")
UNIT_TEST(openMVG solver_resection_kernel "openMVG_multiview_test_data;openMVG_multiview")
UNIT_TEST(openMVG solver_translation_knownRotation_kernel "openMVG_multiview_test_data;openMVG_multiview")

Expand Down
94 changes: 94 additions & 0 deletions src/openMVG/multiview/solver_essential_eight_point_test.cpp
Original file line number Diff line number Diff line change
@@ -0,0 +1,94 @@
// This file is part of OpenMVG, an Open Multiple View Geometry C++ library.

// Copyright (c) 2018 Pierre MOULON.

// This Source Code Form is subject to the terms of the Mozilla Public
// License, v. 2.0. If a copy of the MPL was not distributed with this
// file, You can obtain one at http://mozilla.org/MPL/2.0/.

#include "openMVG/multiview/essential.hpp"
#include "openMVG/multiview/motion_from_essential.hpp"
#include "openMVG/multiview/projection.hpp"
#include "openMVG/multiview/solver_essential_eight_point.hpp"
#include "openMVG/multiview/test_data_sets.hpp"

#include "testing/testing.h"

#include <numeric>
using namespace openMVG;

/// Check that the E matrix fit the Essential Matrix properties
/// Determinant is 0
///
#define EXPECT_ESSENTIAL_MATRIX_PROPERTIES(E, expectedPrecision) { \
EXPECT_NEAR(0, E.determinant(), expectedPrecision); \
const Mat3 O = 2 * E * E.transpose() * E - (E * E.transpose()).trace() * E; \
const Mat3 zero3x3 = Mat3::Zero(); \
EXPECT_MATRIX_NEAR(zero3x3, O, expectedPrecision);\
}

TEST(EightPointsRelativePose, RelativePose_Kernel_IdFocal) {

//-- Setup a circular camera rig and assert that 8PT relative pose solver is working.
const int iNviews = 5;
const NViewDataSet d = NRealisticCamerasRing(iNviews, 8,
nViewDatasetConfigurator(1,1,0,0,5,0)); // Suppose a camera with Unit matrix as K

for (int i=0; i <iNviews; ++i)
{
const int I = i;
const int J = (i+1)%iNviews;
std::vector<Mat3> Es; // Essential,
EightPointRelativePoseSolver::Solve(
d._K[I].inverse() * d._x[I].colwise().homogeneous(),
d._K[J].inverse() * d._x[J].colwise().homogeneous(),
&Es);

CHECK(!Es.empty());

// Recover the relative pose from E.
std::vector<geometry::Pose3> relative_poses;
for (size_t s = 0; s < Es.size(); ++s) {

// Check that E holds the essential matrix constraints.
EXPECT_ESSENTIAL_MATRIX_PROPERTIES(Es[s], 1e-8);
std::vector<uint32_t> index(d._x[I].cols());
std::iota(index.begin(), index.end(), 0);
geometry::Pose3 relative_pose;
if(RelativePoseFromEssential(
d._x[I].colwise().homogeneous(),
d._x[J].colwise().homogeneous(),
Es[s],
index,
&relative_pose))
{
relative_poses.push_back(relative_pose);
}
}

CHECK(!relative_poses.empty());
//-- Compute Ground Truth motion
Mat3 R;
Vec3 t;
RelativeCameraMotion(d._R[I], d._t[I], d._R[J], d._t[J], &R, &t);

// Assert that found relative motion is correct for almost one model.
bool bsolution_found = false;
for (size_t nModel = 0; nModel < relative_poses.size(); ++nModel) {

// Check that we find the correct relative orientation.
if (FrobeniusDistance(R, relative_poses[nModel].rotation()) < 1e-3
&& (t / t.norm()
- relative_poses[nModel].translation()
/ relative_poses[nModel].translation().norm()).norm() < 1e-3 ) {
bsolution_found = true;
}
}
//-- Almost one solution must find the correct relative orientation
CHECK(bsolution_found);
}
}

/* ************************************************************************* */
int main() { TestResult tr; return TestRegistry::runAllTests(tr);}
/* ************************************************************************* */
Loading

0 comments on commit 025344f

Please sign in to comment.