Skip to content

Commit

Permalink
[multiview] Resolve cross dependency with robustEstimation
Browse files Browse the repository at this point in the history
  • Loading branch information
gregoire-dl committed Apr 17, 2019
1 parent bf14eb0 commit 4ba7108
Show file tree
Hide file tree
Showing 100 changed files with 998 additions and 827 deletions.
2 changes: 1 addition & 1 deletion .travis.yml
Original file line number Diff line number Diff line change
Expand Up @@ -104,7 +104,7 @@ script:
fi
cd $GT_TEST_SOURCE
git checkout 1828a5076ccca86fd523c92a768f1d518dfdbb91 # checkout a specific commit to ensure repeatability
python EvaluationLauncher.py -s "$ALICEVISION_BUILD/$BUILD_SYSTEM-$BUILD_PROCESSOR" -i Benchmarking_Camera_Calibration_2008/ -o ${GT_TEST_OUTPUT} -r ${GT_TEST_RESULTS} --limit 3
python EvaluationLauncher.py -s "$ALICEVISION_BUILD/$BUILD_SYSTEM-$BUILD_PROCESSOR" -i Benchmarking_Camera_Calibration_2008/ -o ${GT_TEST_OUTPUT} -r ${GT_TEST_RESULTS} -v --limit 3
cat ${GT_TEST_RESULTS}
# Return to root and remove GT huge files to avoid cache problems
cd $TRAVIS_BUILD_DIR
Expand Down
23 changes: 11 additions & 12 deletions src/aliceVision/camera/CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,24 +1,23 @@
# Headers
set(camera_files_headers
camera.hpp
cameraCommon.hpp
cameraUndistortImage.hpp
IntrinsicBase.hpp
IntrinsicInitMode.hpp
Pinhole.hpp
PinholeBrown.hpp
PinholeFisheye.hpp
PinholeFisheye1.hpp
PinholeRadial.hpp
camera.hpp
cameraCommon.hpp
cameraUndistortImage.hpp
IntrinsicBase.hpp
IntrinsicInitMode.hpp
Pinhole.hpp
PinholeBrown.hpp
PinholeFisheye.hpp
PinholeFisheye1.hpp
PinholeRadial.hpp
)

alicevision_add_interface(aliceVision_camera
SOURCES ${camera_files_headers}
LINKS
aliceVision_numeric
aliceVision_geometry
aliceVision_multiview
aliceVision_image
aliceVision_numeric
aliceVision_stl
aliceVision_system
)
Expand Down
4 changes: 2 additions & 2 deletions src/aliceVision/camera/Pinhole.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -8,10 +8,10 @@
#pragma once

#include <aliceVision/numeric/numeric.hpp>
#include <aliceVision/numeric/projection.hpp>
#include <aliceVision/geometry/Pose3.hpp>
#include <aliceVision/camera/cameraCommon.hpp>
#include <aliceVision/camera/IntrinsicBase.hpp>
#include <aliceVision/geometry/Pose3.hpp>
#include <aliceVision/multiview/projection.hpp>

#include <vector>
#include <sstream>
Expand Down
2 changes: 1 addition & 1 deletion src/aliceVision/geometry/frustumIntersection_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#include "aliceVision/geometry/Frustum.hpp"

#include "aliceVision/multiview/NViewDataSet.hpp"
#include "aliceVision/multiview/projection.hpp"
#include "aliceVision/numeric/projection.hpp"

#include <iostream>

Expand Down
2 changes: 1 addition & 1 deletion src/aliceVision/geometry/rigidTransformation3D.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -147,7 +147,7 @@ bool ACRansac_FindRTS(const Mat& x1,

const KernelT kernel = KernelT(x1, x2);

multiview::MatrixModel<Mat4> RTS;
robustEstimation::MatrixModel<Mat4> RTS;

// robust estimation of the Projection matrix and its precision
const std::pair<double, double> ACRansacOut = robustEstimation::ACRANSAC(kernel, vec_inliers, numIterations, &RTS, dPrecision);
Expand Down
16 changes: 8 additions & 8 deletions src/aliceVision/geometry/rigidTransformation3D.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@

#include <aliceVision/numeric/numeric.hpp>
#include <aliceVision/numeric/LMFunctor.hpp>
#include <aliceVision/multiview/ISolver.hpp>
#include <aliceVision/robustEstimation/ISolver.hpp>

namespace aliceVision {
namespace geometry {
Expand Down Expand Up @@ -150,7 +150,7 @@ void Refine_RTS(const Mat &x1,
/**
* @brief the Solver to use for ACRansac
*/
class RTSSolver : public multiview::ISolver<multiview::MatrixModel<Mat4>>
class RTSSolver : public robustEstimation::ISolver<robustEstimation::MatrixModel<Mat4>>
{
public:

Expand All @@ -173,18 +173,18 @@ class RTSSolver : public multiview::ISolver<multiview::MatrixModel<Mat4>>
}

// solve the RTS problem
inline void solve(const Mat& pts1, const Mat& pts2, std::vector<multiview::MatrixModel<Mat4>>& models) const
inline void solve(const Mat& pts1, const Mat& pts2, std::vector<robustEstimation::MatrixModel<Mat4>>& models) const
{
models.push_back( multiview::MatrixModel<Mat4>(Eigen::umeyama(pts1, pts2, true)) );
models.push_back( robustEstimation::MatrixModel<Mat4>(Eigen::umeyama(pts1, pts2, true)) );
}

void solve(const Mat& x1, const Mat& x2, std::vector<multiview::MatrixModel<Mat4>>& models, const std::vector<double>& weights) const override
void solve(const Mat& x1, const Mat& x2, std::vector<robustEstimation::MatrixModel<Mat4>>& models, const std::vector<double>& weights) const override
{
throw std::logic_error("RTSSolver does not support problem solving with weights.");
}

// compute the residual of the transformation
inline double error(const multiview::MatrixModel<Mat4>& RTS, const Vec3& pt1, const Vec3& pt2)
inline double error(const robustEstimation::MatrixModel<Mat4>& RTS, const Vec3& pt1, const Vec3& pt2)
{
const Mat4& matrixRTS = RTS.getMatrix();
const Mat3& RS = matrixRTS.topLeftCorner<3, 3>();
Expand All @@ -200,7 +200,7 @@ class RTSSolver : public multiview::ISolver<multiview::MatrixModel<Mat4>>
struct RTSSquaredResidualError
{
// return the squared error
inline double error(const multiview::MatrixModel<Mat4>& RTS, const Vec3& pt1, const Vec3& pt2) const
inline double error(const robustEstimation::MatrixModel<Mat4>& RTS, const Vec3& pt1, const Vec3& pt2) const
{
const Mat4& matrixRTS = RTS.getMatrix();
const Mat3& RS = matrixRTS.topLeftCorner<3, 3>();
Expand All @@ -212,7 +212,7 @@ struct RTSSquaredResidualError
/**
* @brief The kernel to use for ACRansac
*/
template <typename SolverT_, typename ErrorT_, typename ModelT_ = multiview::MatrixModel<Mat4>>
template <typename SolverT_, typename ErrorT_, typename ModelT_ = robustEstimation::MatrixModel<Mat4>>
class ACKernelAdaptor_PointsRegistrationSRT
{
public:
Expand Down
4 changes: 2 additions & 2 deletions src/aliceVision/geometry/rigidTransformation3D_test.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -166,7 +166,7 @@ BOOST_AUTO_TEST_CASE(SRT_precision_ACRANSAC_noNoise)
Mat4 RTS;
composeRTS(Sc, tc, Rc, RTS);

multiview::MatrixModel<Mat4> modelRTS(RTS);
robustEstimation::MatrixModel<Mat4> modelRTS(RTS);
geometry::RTSSquaredResidualError errorEstimator;

for(std::size_t i = 0; i < nbPoints; ++i)
Expand Down Expand Up @@ -237,7 +237,7 @@ BOOST_AUTO_TEST_CASE(SRT_precision_ACRANSAC_noiseByShuffling)
Mat4 RTS;
composeRTS(Sc, tc, Rc, RTS);

multiview::MatrixModel<Mat4> modelRTS(RTS);
robustEstimation::MatrixModel<Mat4> modelRTS(RTS);
geometry::RTSSquaredResidualError errorEstimator;

// check the residuals for the inliers
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include "aliceVision/linearProgramming/lInfinityCV/resection_kernel.hpp"
#include "aliceVision/robustEstimation/maxConsensus.hpp"
#include "aliceVision/robustEstimation/ScoreEvaluator.hpp"
#include "aliceVision/multiview/projection.hpp"
#include "aliceVision/numeric/projection.hpp"

#include <iostream>
#include <vector>
Expand Down Expand Up @@ -45,7 +45,7 @@ BOOST_AUTO_TEST_CASE(Resection_L_Infinity_Robust_OutlierFree) {

KernelType kernel(pt2D, pt3D);
ScoreEvaluator<KernelType> scorer(2*Square(0.6));
multiview::Mat34Model P = maxConsensus(kernel, scorer, nullptr, 128);
robustEstimation::Mat34Model P = maxConsensus(kernel, scorer, nullptr, 128);

// Check that Projection matrix is near to the GT :
Mat34 GT_ProjectionMatrix = d.P(nResectionCameraIndex).array()
Expand Down Expand Up @@ -98,7 +98,7 @@ BOOST_AUTO_TEST_CASE(Resection_L_Infinity_Robust_OneOutlier)
const Mat & pt3D = d2._X;
KernelType kernel(pt2D, pt3D);
ScoreEvaluator<KernelType> scorer(Square(0.1)); //Highly intolerant for the test
multiview::Mat34Model P = maxConsensus(kernel, scorer, nullptr, 128);
robustEstimation::Mat34Model P = maxConsensus(kernel, scorer, nullptr, 128);

// Check that Projection matrix is near to the GT :
Mat34 GT_ProjectionMatrix = d.P(nResectionCameraIndex).array()
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@
#include <vector>

#include "aliceVision/multiview/NViewDataSet.hpp"
#include "aliceVision/multiview/projection.hpp"
#include "aliceVision/numeric/projection.hpp"
#include <aliceVision/config.hpp>

#include "aliceVision/linearProgramming/ISolver.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,7 +10,7 @@
#include "aliceVision/numeric/numeric.hpp"
#include <aliceVision/config.hpp>

#include "aliceVision/multiview/projection.hpp"
#include "aliceVision/numeric/projection.hpp"

#include "aliceVision/linearProgramming/ISolver.hpp"
#include "aliceVision/linearProgramming/OSIXSolver.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -8,7 +8,7 @@
#include "aliceVision/multiview/NViewDataSet.hpp"
#include "aliceVision/numeric/numeric.hpp"
#include <aliceVision/config.hpp>
#include "aliceVision/multiview/projection.hpp"
#include "aliceVision/numeric/projection.hpp"
#include "aliceVision/linearProgramming/ISolver.hpp"
#include "aliceVision/linearProgramming/OSIXSolver.hpp"
#if ALICEVISION_IS_DEFINED(ALICEVISION_HAVE_MOSEK)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
#include "aliceVision/numeric/numeric.hpp"
#include <aliceVision/config.hpp>

#include "aliceVision/multiview/projection.hpp"
#include "aliceVision/numeric/projection.hpp"

#include "aliceVision/linearProgramming/ISolver.hpp"
#include "aliceVision/linearProgramming/OSIXSolver.hpp"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ void translate(const Mat3X & X, const Vec3 & vecTranslation,
}
}

void l1SixPointResectionSolver::solve(const Mat &pt2D, const Mat &pt3d, std::vector<multiview::Mat34Model>& Ps) const
void l1SixPointResectionSolver::solve(const Mat &pt2D, const Mat &pt3d, std::vector<robustEstimation::Mat34Model>& Ps) const
{
assert(2 == pt2D.rows());
assert(3 == pt3d.rows());
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -7,8 +7,8 @@

#pragma once

#include <aliceVision/multiview/ISolver.hpp>
#include <aliceVision/multiview/TwoViewKernel.hpp>
#include <aliceVision/robustEstimation/ISolver.hpp>
#include <aliceVision/robustEstimation/FittingKernel.hpp>
#include <aliceVision/multiview/resection/ProjectionDistanceError.hpp>
#include <aliceVision/numeric/numeric.hpp>

Expand All @@ -24,7 +24,7 @@ namespace kernel {
* Rely on L1 Resection algorithm.
* Work from 6 to N points.
*/
struct l1SixPointResectionSolver : public multiview::ISolver<multiview::Mat34Model>
struct l1SixPointResectionSolver : public robustEstimation::ISolver<robustEstimation::Mat34Model>
{
/**
* @brief Return the minimum number of required samples
Expand All @@ -48,7 +48,7 @@ struct l1SixPointResectionSolver : public multiview::ISolver<multiview::Mat34Mod
* @brief Solve the problem of camera pose.
* @note First 3d point will be translated in order to have X0 = (0,0,0,1)
*/
void solve(const Mat& pt2D, const Mat& pt3D, std::vector<multiview::Mat34Model>& P) const;
void solve(const Mat& pt2D, const Mat& pt3D, std::vector<robustEstimation::Mat34Model>& P) const;

/**
* @brief Solve the problem.
Expand All @@ -57,7 +57,7 @@ struct l1SixPointResectionSolver : public multiview::ISolver<multiview::Mat34Mod
* @param[out] models A vector into which the computed models are stored.
* @param[in] weights.
*/
void solve(const Mat& x1, const Mat& x2, std::vector<multiview::Mat34Model>& models, const std::vector<double>& weights) const override
void solve(const Mat& x1, const Mat& x2, std::vector<robustEstimation::Mat34Model>& models, const std::vector<double>& weights) const override
{
throw std::logic_error("l1SixPointResectionSolver does not support problem solving with weights.");
}
Expand All @@ -67,7 +67,7 @@ struct l1SixPointResectionSolver : public multiview::ISolver<multiview::Mat34Mod
/**
* @brief Usable solver for the l1 6pt Resection Estimation
*/
typedef multiview::TwoViewKernel<l1SixPointResectionSolver, multiview::resection::ProjectionDistanceError, multiview::Mat34Model> l1PoseResectionKernel;
typedef robustEstimation::FittingKernel<l1SixPointResectionSolver, multiview::resection::ProjectionDistanceError, robustEstimation::Mat34Model> l1PoseResectionKernel;

} // namespace kernel
} // namespace lInfinityCV
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,8 +10,8 @@
#include "aliceVision/numeric/numeric.hpp"
#include "aliceVision/config.hpp"

#include "aliceVision/multiview/projection.hpp"
#include "aliceVision/multiview/conditioning.hpp"
#include "aliceVision/numeric/projection.hpp"
#include "aliceVision/robustEstimation/conditioning.hpp"
#include "aliceVision/multiview/triangulation/Triangulation.hpp"

// Linear programming solver(s)
Expand Down
4 changes: 2 additions & 2 deletions src/aliceVision/localization/VoctreeLocalizer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -1135,9 +1135,9 @@ bool VoctreeLocalizer::robustMatching(matching::RegionsDatabaseMatcherPerDesc &
// So we ignore the previous matches and recompute all matches.
out_featureMatches.clear();

multiview::Mat3Model model(geometricFilter.m_F);
robustEstimation::Mat3Model model(geometricFilter.m_F);

robustEstimation::guidedMatching<multiview::Mat3Model, multiview::relativePose::FundamentalEpipolarDistanceError>(
robustEstimation::guidedMatching<robustEstimation::Mat3Model, multiview::relativePose::FundamentalEpipolarDistanceError>(
model,
queryIntrinsicsBase, // camera::IntrinsicBase of the matched image
matchers.getDatabaseRegionsPerDesc(), // feature::Regions
Expand Down
1 change: 0 additions & 1 deletion src/aliceVision/localization/rigResection.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,6 @@

#include "rigResection.hpp"
#include <aliceVision/system/Logger.hpp>
#include <aliceVision/robustEstimation/RansacKernel.hpp>
#include <aliceVision/robustEstimation/supportEstimation.hpp>

#if ALICEVISION_IS_DEFINED(ALICEVISION_HAVE_OPENGV)
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -10,12 +10,12 @@
#include <aliceVision/types.hpp>
#include <aliceVision/matching/IndMatch.hpp>
#include <aliceVision/matchingImageCollection/GeometricFilterMatrix.hpp>
#include <aliceVision/multiview/essential.hpp>
#include <aliceVision/multiview/relativePose/Essential5PSolver.hpp>
#include <aliceVision/multiview/relativePose/FundamentalError.hpp>
#include <aliceVision/robustEstimation/ACRansac.hpp>
#include <aliceVision/robustEstimation/RansacKernel.hpp>
#include <aliceVision/robustEstimation/guidedMatching.hpp>
#include <aliceVision/multiview/relativePose/Essential5PSolver.hpp>
#include <aliceVision/multiview/relativePose/FundamentalError.hpp>
#include <aliceVision/multiview/essential.hpp>
#include <aliceVision/multiview/RelativePoseKernel.hpp>
#include <aliceVision/feature/RegionsPerView.hpp>
#include <aliceVision/sfmData/SfMData.hpp>

Expand Down Expand Up @@ -46,9 +46,6 @@ struct GeometricFilterMatrix_E_AC : public GeometricFilterMatrix
const matching::MatchesPerDescType& putativeMatchesPerType,
matching::MatchesPerDescType& out_geometricInliersPerType)
{
using namespace aliceVision;
using namespace aliceVision::robustEstimation;

out_geometricInliersPerType.clear();

// get back corresponding view index
Expand Down Expand Up @@ -79,10 +76,10 @@ struct GeometricFilterMatrix_E_AC : public GeometricFilterMatrix
fillMatricesWithUndistortFeaturesMatches(pairIndex, putativeMatchesPerType, sfmData, regionsPerView, descTypes, xI, xJ);

// define the AContrario adapted Essential matrix solver
typedef RelativePoseKernel_K<
typedef multiview::RelativePoseKernel_K<
multiview::relativePose::Essential5PSolver,
multiview::relativePose::FundamentalEpipolarDistanceError,
multiview::Mat3Model>
robustEstimation::Mat3Model>
KernelT;

const camera::Pinhole* ptrPinholeI = (const camera::Pinhole*)(camI);
Expand All @@ -95,8 +92,8 @@ struct GeometricFilterMatrix_E_AC : public GeometricFilterMatrix
const double upperBoundPrecision = Square(m_dPrecision);

std::vector<std::size_t> inliers;
multiview::Mat3Model model;
const std::pair<double,double> ACRansacOut = ACRANSAC(kernel, inliers, m_stIteration, &model, upperBoundPrecision);
robustEstimation::Mat3Model model;
const std::pair<double,double> ACRansacOut = robustEstimation::ACRANSAC(kernel, inliers, m_stIteration, &model, upperBoundPrecision);
m_E = model.getMatrix();

if (inliers.empty())
Expand Down Expand Up @@ -157,9 +154,9 @@ struct GeometricFilterMatrix_E_AC : public GeometricFilterMatrix
Mat3 F;
fundamentalFromEssential(m_E, ptrPinholeI->K(), ptrPinholeJ->K(), &F);

multiview::Mat3Model model(F);
robustEstimation::Mat3Model model(F);
// multiview::relativePose::FundamentalSymmetricEpipolarDistanceError
robustEstimation::guidedMatching<multiview::Mat3Model, multiview::relativePose::FundamentalEpipolarDistanceError>(
robustEstimation::guidedMatching<robustEstimation::Mat3Model, multiview::relativePose::FundamentalEpipolarDistanceError>(
model,
camI, regionsPerView.getAllRegions(I),
camJ, regionsPerView.getAllRegions(J),
Expand Down
Loading

0 comments on commit 4ba7108

Please sign in to comment.