Commit 2a14d220 authored by edgarriba's avatar edgarriba

gsoc_2015: sfm module integration

parent 2de6ff57
set(the_description "SFM algorithms")
### LIBMV LIGHT EXTERNAL DEPENDENCIES ###
find_package(Ceres QUIET)
if(NOT DEFINED SFM_DEPS_OK)
set(_fname "${CMAKE_CURRENT_BINARY_DIR}/test_sfm_deps.cpp")
file(WRITE "${_fname}" "#include <glog/logging.h>\n#include <gflags/gflags.h>\nint main() { (void)(0); return 0; }\n")
try_compile(SFM_DEPS_OK "${CMAKE_CURRENT_BINARY_DIR}" "${_fname}"
CMAKE_FLAGS "-DINCLUDE_DIRECTORIES:STRING=${GLOG_INCLUDE_DIRS};${GFLAGS_INCLUDE_DIRS}"
LINK_LIBRARIES ${GLOG_LIBRARIES} ${GFLAGS_LIBRARIES}
OUTPUT_VARIABLE OUTPUT
)
file(REMOVE "${_fname}")
message(STATUS "Checking SFM deps... ${SFM_DEPS_OK}")
endif()
if(NOT HAVE_EIGEN OR NOT SFM_DEPS_OK)
set(DISABLE_MSG "Module opencv_sfm disabled because the following dependencies are not found:")
if(NOT HAVE_EIGEN)
set(DISABLE_MSG "${DISABLE_MSG} Eigen")
endif()
if(NOT SFM_DEPS_OK)
set(DISABLE_MSG "${DISABLE_MSG} Glog/Gflags")
endif()
message(STATUS ${DISABLE_MSG})
ocv_module_disable(sfm)
endif()
### LIBMV LIGHT DEFINITIONS ###
set(LIBMV_LIGHT_INCLUDES
src/libmv_light
"${OpenCV_SOURCE_DIR}/include/opencv"
"${GLOG_INCLUDE_DIRS}"
"${GFLAGS_INCLUDE_DIRS}"
)
set(LIBMV_LIGHT_LIBS
correspondence
multiview
numeric
${GLOG_LIBRARIES}
${GFLAGS_LIBRARIES}
)
if(Ceres_FOUND)
add_definitions("-DCERES_FOUND=1")
list(APPEND LIBMV_LIGHT_LIBS simple_pipeline)
else()
add_definitions("-DCERES_FOUND=0")
message(STATUS "CERES support is disabled. Ceres Solver for reconstruction API is required.")
endif()
### DEFINE OPENCV SFM MODULE DEPENDENCIES ###
### CREATE OPENCV SFM MODULE ###
ocv_add_module(sfm
opencv_core
opencv_calib3d
opencv_features2d
opencv_xfeatures2d
)
ocv_warnings_disable(CMAKE_CXX_FLAGS
-Wundef
-Wshadow
-Wsign-compare
-Wmissing-declarations
-Wunused-but-set-variable
-Wunused-parameter
-Wunused-function
)
if(UNIX)
if(CMAKE_COMPILER_IS_GNUCXX OR CV_ICC)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -fPIC")
endif()
endif()
ocv_include_directories( ${LIBMV_LIGHT_INCLUDES} )
ocv_module_include_directories()
# source files
FILE(GLOB OPENCV_SFM_SRC src/*.cpp)
# define the header files (make the headers appear in IDEs.)
FILE(GLOB OPENCV_SFM_HDRS include/opencv2/sfm/*.hpp)
ocv_set_module_sources(HEADERS ${OPENCV_SFM_HDRS}
SOURCES ${OPENCV_SFM_SRC})
ocv_create_module()
# build libmv_light
if(NOT CMAKE_VERSION VERSION_LESS 2.8.11) # See ocv_target_include_directories() implementation
if(TARGET ${the_module})
get_target_property(__include_dirs ${the_module} INCLUDE_DIRECTORIES)
include_directories(${__include_dirs})
endif()
endif()
include_directories(${OCV_TARGET_INCLUDE_DIRS_${the_module}})
add_subdirectory(src/libmv_light)
ocv_target_link_libraries(${the_module} ${LIBMV_LIGHT_LIBS})
### CREATE OPENCV SFM TESTS ###
ocv_add_accuracy_tests()
### CREATE OPENCV SFM SAMPLES ###
if(Ceres_FOUND)
ocv_add_samples(opencv_viz)
endif ()
Structure From Motion module
============================
This module contains algorithms to perform 3d reconstruction from 2d images. The core of the module is a light version of [Libmv](https://developer.blender.org/project/profile/59), which is a Library for Multiview Reconstruction (or LMV) divided into different modules (correspondence/numeric/multiview/simple_pipeline) that allow to resolve part of the SfM process.
Dependencies
------------
Before compiling, take a look at the following details in order to give a proper use of the Struncture from Motion module. **Advice:** The module is only available for Linux/GNU systems.
In addition, it depends on some open source libraries:
- [Eigen](http://eigen.tuxfamily.org/index.php?title=Main_Page) 3.2.2 or later. **Required**
- [Google Log](http://code.google.com/p/google-glog) 0.3.1 or later. **Required**
- [Google Flags](http://code.google.com/p/gflags). **Required**
- [Ceres Solver](http://ceres-solver.org). Needed by the reconstruction API in order to solve part of the Bundle Adjustment plus the points Intersect. If Ceres Solver is not installed on your system, the reconstruction funcionality will be disabled. **Recommended**
Installation
------------
**Required Dependencies**
In case you are on [Ubuntu](http://www.ubuntu.com/) you can simply install the required dependencies by typing the following command.
sudo apt-get install libeigen3-dev libgflags-dev libgoogle-glog-dev
**Ceres Solver**
Start by installing all the dependencies.
# CMake
sudo apt-get install cmake
# google-glog + gflags
sudo apt-get install libgoogle-glog-dev
# BLAS & LAPACK
sudo apt-get install libatlas-base-dev
# Eigen3
sudo apt-get install libeigen3-dev
# SuiteSparse and CXSparse (optional)
# - If you want to build Ceres as a *static* library (the default)
# you can use the SuiteSparse package in the main Ubuntu package
# repository:
sudo apt-get install libsuitesparse-dev
# - However, if you want to build Ceres as a *shared* library, you must
# add the following PPA:
sudo add-apt-repository ppa:bzindovic/suitesparse-bugfix-1319687
sudo apt-get update
sudo apt-get install libsuitesparse-dev
We are now ready to build, test, and install Ceres.
git clone https://ceres-solver.googlesource.com/ceres-solver
cd ceres-solver
mkdir build && cd build
cmake ..
make -j4
make test
sudo make install
Usage
-----
**trajectory_reconstruction.cpp**
This program shows the camera trajectory reconstruction capabilities in the OpenCV Structure From Motion (SFM) module. It loads a file with the tracked 2d points over all the frames which are embedded into a vector of 2d points array, where each inner array represents a different frame. Every frame is composed by a list of 2d points which e.g. the first point in frame 1 is the same point in frame 2. If there is no point in a frame the assigned value will be (-1,-1).
To run this example you can type the following command in the opencv binaries directory specifying the file path in your system and the camera intrinsics (in this case the tracks file was obtained using Blender Motion module).
./example_sfm_trajectory_reconstruction tracks_file.txt 1914 640 360
Finally, the script reconstructs the given set of tracked points and show the result using the OpenCV 3D visualizer (viz). On the image below, it's shown a screenshot with the result you should obtain running the "desktop_tracks.txt" found inside the samples directory.
<p align="center">
<img src="doc/pics/desktop_trajectory.png" width="400" height="300">
</p>
**scene_reconstruction.cpp**
This program shows the multiview scene reconstruction capabilities in the OpenCV Structure From Motion (SFM) module. It calls the recontruction API using the overloaded signature for real images. In this case the script loads a file which provides a list with all the image paths that we want to reconstruct. Internally, this script extract and compute the sparse 2d features using DAISY descriptors which are matched using FlannBasedMatcher to finally build the tracks structure.
To run this example you can type the following command in the opencv binaries directory specifying the file path and the camera intrinsics.
./example_sfm_scene_reconstruction image_paths_file.txt 350 240 360
This sample shows the estimated camera trajectory plus the sparse 3D reconstruction using the the OpenCV 3D visualizer (viz).
On the next pictures, it's shown a screenshot where you can see the used images as input from the "Temple of the Dioskouroi" [1] and the obtained result after running the reconstruction API.
<p align="center">
<img src="doc/pics/temple_input.jpg" width="800" height="200">
</p>
<p align="center">
<img src="doc/pics/temple_reconstruction.jpg" width="400" height="250">
</p>
On the next pictures, it's shown a screenshot where you can see the used images as input from la Sagrada Familia (BCN) [2] which you can find in the samples directory and the obtained result after running the reconstruction API.
<p align="center">
<img src="doc/pics/sagrada_familia_input.jpg" width="700" height="250">
</p>
<p align="center">
<img src="doc/pics/sagrada_familia_reconstruction.jpg" width="400" height="250">
</p>
[1] [http://vision.middlebury.edu/mview/data](http://vision.middlebury.edu/mview/data)
[2] Penate Sanchez, A. and Moreno-Noguer, F. and Andrade Cetto, J. and Fleuret, F. (2014). LETHA: *Learning from High Quality Inputs for 3D Pose Estimation in Low Quality Images*. Proceedings of the International Conference on 3D vision (3DV). [[URL]](http://www.iri.upc.edu/research/webprojects/pau/datasets/sagfam)
Future Work
-----------
* Update signatures documentation.
* Add prototype for dense reconstruction once is working (DAISY paper implementation).
* Decide which functions are kept since most of them are the same in calib3d.
* Finish to implement computeOrientation().
* Find a good features matchig algorithm for reconstruction() in case we provide pure images for autocalibration (look into OpenMVG).
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, Willow Garage, Inc.
* 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 Willow Garage, Inc. 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 OWNER 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.
*
*/
#ifndef __OPENCV_SFM_HPP__
#define __OPENCV_SFM_HPP__
#include <opencv2/sfm/conditioning.hpp>
#include <opencv2/sfm/fundamental.hpp>
#include <opencv2/sfm/numeric.hpp>
#include <opencv2/sfm/projection.hpp>
#include <opencv2/sfm/triangulation.hpp>
#if CERES_FOUND
#include <opencv2/sfm/reconstruct.hpp>
#include <opencv2/sfm/simple_pipeline.hpp>
#endif
/** @defgroup sfm Structure From Motion
The opencv_sfm module contains algorithms to perform 3d reconstruction
from 2d images.\n
The core of the module is based on a light version of
[Libmv](https://developer.blender.org/project/profile/59) originally
developed by Sameer Agarwal and Keir Mierle.
__Whats is libmv?__ \n
libmv, also known as the Library for Multiview Reconstruction (or LMV),
is the computer vision backend for Blender's motion tracking abilities.
Unlike other vision libraries with general ambitions, libmv is focused
on algorithms for match moving, specifically targeting [Blender](https://developer.blender.org) as the
primary customer. Dense reconstruction, reconstruction from unorganized
photo collections, image recognition, and other tasks are not a focus
of libmv.
__Development__ \n
libmv is officially under the Blender umbrella, and so is developed
on developer.blender.org. The [source repository](https://developer.blender.org/diffusion/LMV) can get checked out
independently from Blender.
This module has been originally developed as a project for Google Summer of Code 2012-2015.
@note
- Notice that it is compiled only when Eigen, GLog and GFlags are correctly installed.\n
Check installation instructions in the following tutorial: @ref tutorial_sfm_installation
@{
@defgroup conditioning Conditioning
@defgroup fundamental Fundamental
@defgroup numeric Numeric
@defgroup projection Projection
@defgroup robust Robust Estimation
@defgroup triangulation Triangulation
@defgroup reconstruction Reconstruction
@note
- Notice that it is compiled only when Ceres Solver is correctly installed.\n
Check installation instructions in the following tutorial: @ref tutorial_sfm_installation
@defgroup simple_pipeline Simple Pipeline
@note
- Notice that it is compiled only when Ceres Solver is correctly installed.\n
Check installation instructions in the following tutorial: @ref tutorial_sfm_installation
@}
*/
#endif
/* End of file. */
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, Willow Garage, Inc.
* 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 Willow Garage, Inc. 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 OWNER 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.
*
*/
#ifndef __OPENCV_CONDITIONING_HPP__
#define __OPENCV_CONDITIONING_HPP__
#include <opencv2/core.hpp>
namespace cv
{
namespace sfm
{
//! @addtogroup conditioning
//! @{
/** Point conditioning (non isotropic).
@param points Input vector of N-dimensional points.
@param T Output 3x3 transformation matrix.
Computes the transformation matrix such that the two principal moments of the set of points are equal to unity,
forming an approximately symmetric circular cloud of points of radius 1 about the origin.\n
Reference: @cite HartleyZ00 4.4.4 pag.109
*/
CV_EXPORTS
void
preconditionerFromPoints( InputArray points,
OutputArray T );
/** @brief Point conditioning (isotropic).
@param points Input vector of N-dimensional points.
@param T Output 3x3 transformation matrix.
Computes the transformation matrix such that each coordinate direction will be scaled equally,
bringing the centroid to the origin with an average centroid \f$(1,1,1)^T\f$.\n
Reference: @cite HartleyZ00 4.4.4 pag.107.
*/
CV_EXPORTS
void
isotropicPreconditionerFromPoints( InputArray points,
OutputArray T );
/** @brief Apply Transformation to points.
@param points Input vector of N-dimensional points.
@param T Input 3x3 transformation matrix such that \f$x = T*X\f$, where \f$X\f$ are the points to transform and \f$x\f$ the transformed points.
@param transformed_points Output vector of N-dimensional transformed points.
*/
CV_EXPORTS
void
applyTransformationToPoints( InputArray points,
InputArray T,
OutputArray transformed_points );
/** @brief This function normalizes points (non isotropic).
@param points Input vector of N-dimensional points.
@param normalized_points Output vector of the same N-dimensional points but with mean 0 and average norm \f$\sqrt{2}\f$.
@param T Output 3x3 transform matrix such that \f$x = T*X\f$, where \f$X\f$ are the points to normalize and \f$x\f$ the normalized points.
Internally calls @ref preconditionerFromPoints in order to get the scaling matrix before applying @ref applyTransformationToPoints.
This operation is an essential step before applying the DLT algorithm in order to consider the result as optimal.\n
Reference: @cite HartleyZ00 4.4.4 pag.109
*/
CV_EXPORTS
void
normalizePoints( InputArray points,
OutputArray normalized_points,
OutputArray T );
/** @brief This function normalizes points. (isotropic).
@param points Input vector of N-dimensional points.
@param normalized_points Output vector of the same N-dimensional points but with mean 0 and average norm \f$\sqrt{2}\f$.
@param T Output 3x3 transform matrix such that \f$x = T*X\f$, where \f$X\f$ are the points to normalize and \f$x\f$ the normalized points.
Internally calls @ref preconditionerFromPoints in order to get the scaling matrix before applying @ref applyTransformationToPoints.
This operation is an essential step before applying the DLT algorithm in order to consider the result as optimal.\n
Reference: @cite HartleyZ00 4.4.4 pag.107.
*/
CV_EXPORTS
void
normalizeIsotropicPoints( InputArray points,
OutputArray normalized_points,
OutputArray T );
//! @} sfm
} /* namespace sfm */
} /* namespace cv */
#endif
/* End of file. */
\ No newline at end of file
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, Willow Garage, Inc.
* 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 Willow Garage, Inc. 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 OWNER 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.
*
*/
#ifndef __OPENCV_SFM_FUNDAMENTAL_HPP__
#define __OPENCV_SFM_FUNDAMENTAL_HPP__
#include <vector>
#include <opencv2/core.hpp>
namespace cv
{
namespace sfm
{
//! @addtogroup fundamental
//! @{
/** @brief Get projection matrices from Fundamental matrix
@param F Input 3x3 fundamental matrix.
@param P1 Output 3x4 one possible projection matrix.
@param P2 Output 3x4 another possible projection matrix.
*/
CV_EXPORTS
void
projectionsFromFundamental( InputArray F,
OutputArray P1,
OutputArray P2 );
/** @brief Get Fundamental matrix from Projection matrices.
@param P1 Input 3x4 first projection matrix.
@param P2 Input 3x4 second projection matrix.
@param F Output 3x3 fundamental matrix.
*/
CV_EXPORTS
void
fundamentalFromProjections( InputArray P1,
InputArray P2,
OutputArray F );
/** @brief Estimate the fundamental matrix between two dataset of 2D point (image coords space).
@param x1 Input 2xN Array of 2D points in view 1.
@param x2 Input 2xN Array of 2D points in view 2.
@param F Output 3x3 fundamental matrix.
Uses the normalized 8-point fundamental matrix solver.
Reference: @cite HartleyZ00 11.2 pag.281 (x1 = x, x2 = x')
*/
CV_EXPORTS
void
normalizedEightPointSolver( InputArray x1,
InputArray x2,
OutputArray F );
/** @brief Computes the relative camera motion between two cameras.
@param R1 Input 3x3 first camera rotation matrix.
@param t1 Input 3x1 first camera translation vector.
@param R2 Input 3x3 second camera rotation matrix.
@param t2 Input 3x1 second camera translation vector.
@param R Output 3x3 relative rotation matrix.
@param t Output 3x1 relative translation vector.
Given the motion parameters of two cameras, computes the motion parameters
of the second one assuming the first one to be at the origin.
If T1 and T2 are the camera motions, the computed relative motion is \f$T = T_2 T_1^{-1}\f$
*/
CV_EXPORTS
void
relativeCameraMotion( InputArray R1,
InputArray t1,
InputArray R2,
InputArray t2,
OutputArray R,
OutputArray t );
/** Get Motion (R's and t's ) from Essential matrix.
@param E Input 3x3 essential matrix.
@param Rs Output vector of 3x3 rotation matrices.
@param ts Output vector of 3x1 translation vectors.
Reference: @cite HartleyZ00 9.6 pag 259 (Result 9.19)
*/
CV_EXPORTS
void
motionFromEssential( InputArray E,
OutputArrayOfArrays Rs,
OutputArrayOfArrays ts );
/** Choose one of the four possible motion solutions from an essential matrix.
@param Rs Input vector of 3x3 rotation matrices.
@param ts Input vector of 3x1 translation vectors.
@param K1 Input 3x3 first camera matrix \f$K = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$.
@param x1 Input 2x1 vector with first 2d point.
@param K2 Input 3x3 second camera matrix. The parameters are similar to K1.
@param x2 Input 2x1 vector with second 2d point.
Decides the right solution by checking that the triangulation of a match
x1--x2 lies in front of the cameras. Return index of the right solution or -1 if no solution.
Reference: See @cite HartleyZ00 9.6 pag 259 (9.6.3 Geometrical interpretation of the 4 solutions).
*/
CV_EXPORTS
int motionFromEssentialChooseSolution( InputArrayOfArrays Rs,
InputArrayOfArrays ts,
InputArray K1,
InputArray x1,
InputArray K2,
InputArray x2 );
/** @brief Get Essential matrix from Fundamental and Camera matrices.
@param E Input 3x3 essential matrix.
@param K1 Input 3x3 first camera matrix \f$K = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$.
@param K2 Input 3x3 second camera matrix. The parameters are similar to K1.
@param F Output 3x3 fundamental matrix.
Reference: @cite HartleyZ00 9.6 pag 257 (formula 9.12) or http://ai.stanford.edu/~birch/projective/node20.html
*/
CV_EXPORTS
void
fundamentalFromEssential( InputArray E,
InputArray K1,
InputArray K2,
OutputArray F );
/** @brief Get Essential matrix from Fundamental and Camera matrices.
@param F Input 3x3 fundamental matrix.
@param K1 Input 3x3 first camera matrix \f$K = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$.
@param K2 Input 3x3 second camera matrix. The parameters are similar to K1.
@param E Output 3x3 essential matrix.
Reference: @cite HartleyZ00 9.6 pag 257 (formula 9.12)
*/
CV_EXPORTS
void
essentialFromFundamental( InputArray F,
InputArray K1,
InputArray K2,
OutputArray E );
/** @brief Get Essential matrix from Motion (R's and t's ).
@param R1 Input 3x3 first camera rotation matrix.
@param t1 Input 3x1 first camera translation vector.
@param R2 Input 3x3 second camera rotation matrix.
@param t2 Input 3x1 second camera translation vector.
@param E Output 3x3 essential matrix.
Reference: @cite HartleyZ00 9.6 pag 257 (formula 9.12)
*/
CV_EXPORTS
void
essentialFromRt( InputArray R1,
InputArray t1,
InputArray R2,
InputArray t2,
OutputArray E );
/** @brief Normalizes the Fundamental matrix.
@param F Input 3x3 fundamental matrix.
@param F_normalized Output 3x3 normalized fundamental matrix.
By default divides the fundamental matrix by its L2 norm.
*/
CV_EXPORTS
void
normalizeFundamental( InputArray F,
OutputArray F_normalized );
/** @brief Computes Absolute or Exterior Orientation (Pose Estimation) between 2 sets of 3D point.
@param x1 Input first 3xN or 2xN array of points.
@param x2 Input second 3xN or 2xN array of points.
@param R Output 3x3 computed rotation matrix.
@param t Output 3x1 computed translation vector.
@param s Output computed scale factor.
Find the best transformation such that xp=projection*(s*R*x+t) (same as Pose Estimation, ePNP).
The routines below are only for the orthographic case for now.
*/
CV_EXPORTS
void
computeOrientation( InputArrayOfArrays x1,
InputArrayOfArrays x2,
OutputArray R,
OutputArray t,
double s );
//! @} sfm
} /* namespace sfm */
} /* namespace cv */
#endif
/* End of file. */
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, Willow Garage, Inc.
* 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 Willow Garage, Inc. 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 OWNER 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.
*
*/
#ifndef __OPENCV_SFM_NUMERIC_HPP__
#define __OPENCV_SFM_NUMERIC_HPP__
#include <opencv2/core.hpp>
#include <Eigen/Core>
namespace cv
{
namespace sfm
{
//! @addtogroup numeric
//! @{
/** @brief Computes the mean and variance of a given matrix along its rows.
@param A Input NxN matrix.
@param mean Output Nx1 matrix with computed mean.
@param variance Output Nx1 matrix with computed variance.
It computes in the same way as woud do @ref reduce but with \a Variance function.
*/
CV_EXPORTS
void
meanAndVarianceAlongRows( InputArray A,
OutputArray mean,
OutputArray variance );
/** @brief Returns the 3x3 skew symmetric matrix of a vector.
@param x Input 3x1 vector.
Reference: @cite HartleyZ00, p581, equation (A4.5).
*/
CV_EXPORTS
Mat
skew( InputArray x );
///** @brief Returns the skew anti-symmetric matrix of a vector.
// @param x Input 3x3 matrix.
//*/
//CV_EXPORTS
//Matx33d
//skewMat( const Vec3d &x );
//
///** @brief Returns the skew anti-symmetric matrix of a vector with only the first two (independent) lines.
// @param x Input 3x3 matrix.
//*/
//CV_EXPORTS
//Matx33d
//skewMatMinimal( const Vec3d &x );
//! @} numeric
} /* namespace sfm */
} /* namespace cv */
#endif
/* End of file. */
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, Willow Garage, Inc.
* 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 Willow Garage, Inc. 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 OWNER 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.
*
*/
#ifndef __OPENCV_PROJECTION_HPP__
#define __OPENCV_PROJECTION_HPP__
#include <opencv2/core.hpp>
namespace cv
{
namespace sfm
{
//! @addtogroup projection
//! @{
/** @brief Converts point coordinates from homogeneous to euclidean pixel coordinates. E.g., ((x,y,z)->(x/z, y/z))
@param src Input vector of N-dimensional points.
@param dst Output vector of N-1-dimensional points.
*/
CV_EXPORTS
void
homogeneousToEuclidean(InputArray src, OutputArray dst);
/** @brief Converts points from Euclidean to homogeneous space. E.g., ((x,y)->(x,y,1))
@param src Input vector of N-dimensional points.
@param dst Output vector of N+1-dimensional points.
*/
CV_EXPORTS
void
euclideanToHomogeneous(InputArray src, OutputArray dst);
/** @brief Get projection matrix P from K, R and t.
@param K Input 3x3 camera matrix \f$K = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$.
@param R Input 3x3 rotation matrix.
@param t Input 3x1 translation vector.
@param P Output 3x4 projection matrix.
This function estimate the projection matrix by solving the following equation: \f$P = K * [R|t]\f$
*/
CV_EXPORTS
void
projectionFromKRt(InputArray K, InputArray R, InputArray t, OutputArray P);
/** @brief Get K, R and t from projection matrix P, decompose using the RQ decomposition.
@param P Input 3x4 projection matrix.
@param K Output 3x3 camera matrix \f$K = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$.
@param R Output 3x3 rotation matrix.
@param t Output 3x1 translation vector.
Reference: @cite HartleyZ00 A4.1.1 pag.579
*/
CV_EXPORTS
void
KRtFromProjection( InputArray P, OutputArray K, OutputArray R, OutputArray t );
/** @brief Returns the depth of a point transformed by a rigid transform.
@param R Input 3x3 rotation matrix.
@param t Input 3x1 translation vector.
@param X Input 3x1 or 4x1 vector with the 3d point.
*/
CV_EXPORTS
double
depth( InputArray R, InputArray t, InputArray X);
//! @} sfm
} /* namespace sfm */
} /* namespace cv */
#endif
/* End of file. */
/*M///////////////////////////////////////////////////////////////////////////////////////
//
// IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
//
// By downloading, copying, installing or using the software you agree to this license.
// If you do not agree to this license, do not download, install,
// copy or use the software.
//
//
// License Agreement
// For Open Source Computer Vision Library
//
// Copyright (C) 2015, OpenCV Foundation, all rights reserved.
// Third party copyrights are property of their respective owners.
//
// Redistribution and use in source and binary forms, with or without modification,
// are permitted provided that the following conditions are met:
//
// * Redistribution's of source code must retain the above copyright notice,
// this list of conditions and the following disclaimer.
//
// * Redistribution's 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.
//
// * The name of the copyright holders may not 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 Intel Corporation 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.
//
//M*/
#ifndef __OPENCV_SFM_RECONSTRUCT_HPP__
#define __OPENCV_SFM_RECONSTRUCT_HPP__
#include <vector>
#include <string>
#include <opencv2/core.hpp>
namespace cv
{
namespace sfm
{
//! @addtogroup reconstruction
//! @{
#if defined(CV_DOXYGEN) || defined(CERES_FOUND)
/** @brief Reconstruct 3d points from 2d correspondences while performing autocalibration.
@param points2d Input vector of vectors of 2d points (the inner vector is per image).
@param Ps Output vector with the 3x4 projections matrices of each image.
@param points3d Output array with estimated 3d points.
@param K Input/Output camera matrix \f$K = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$. Input parameters used as initial guess.
@param is_projective if true, the cameras are supposed to be projective.
This method calls below signature and extracts projection matrices from estimated K, R and t.
@note
- Tracks must be as precise as possible. It does not handle outliers and is very sensible to them.
*/
CV_EXPORTS
void
reconstruct(InputArrayOfArrays points2d, OutputArray Ps, OutputArray points3d, InputOutputArray K,
bool is_projective = false);
/** @brief Reconstruct 3d points from 2d correspondences while performing autocalibration.
@param points2d Input vector of vectors of 2d points (the inner vector is per image).
@param Rs Output vector of 3x3 rotations of the camera.
@param Ts Output vector of 3x1 translations of the camera.
@param points3d Output array with estimated 3d points.
@param K Input/Output camera matrix \f$K = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$. Input parameters used as initial guess.
@param is_projective if true, the cameras are supposed to be projective.
Internally calls libmv simple pipeline routine with some default parameters by instatiating SFMLibmvEuclideanReconstruction class.
@note
- Tracks must be as precise as possible. It does not handle outliers and is very sensible to them.
- To see a working example for camera motion reconstruction, check the following tutorial: @ref tutorial_sfm_trajectory_estimation.
*/
CV_EXPORTS
void
reconstruct(InputArrayOfArrays points2d, OutputArray Rs, OutputArray Ts, InputOutputArray K,
OutputArray points3d, bool is_projective = false);
/** @brief Reconstruct 3d points from 2d images while performing autocalibration.
@param images a vector of string with the images paths.
@param Ps Output vector with the 3x4 projections matrices of each image.
@param points3d Output array with estimated 3d points.
@param K Input/Output camera matrix \f$K = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$. Input parameters used as initial guess.
@param is_projective if true, the cameras are supposed to be projective.
This method calls below signature and extracts projection matrices from estimated K, R and t.
@note
- The images must be ordered as they were an image sequence. Additionally, each frame should be as close as posible to the previous and posterior.
- For now DAISY features are used in order to compute the 2d points tracks and it only works for 3-4 images.
*/
CV_EXPORTS
void
reconstruct(const std::vector<std::string> images, OutputArray Ps, OutputArray points3d,
InputOutputArray K, bool is_projective = false);
/** @brief Reconstruct 3d points from 2d images while performing autocalibration.
@param images a vector of string with the images paths.
@param Rs Output vector of 3x3 rotations of the camera.
@param Ts Output vector of 3x1 translations of the camera.
@param points3d Output array with estimated 3d points.
@param K Input/Output camera matrix \f$K = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\f$. Input parameters used as initial guess.
@param is_projective if true, the cameras are supposed to be projective.
Internally calls libmv simple pipeline routine with some default parameters by instatiating SFMLibmvEuclideanReconstruction class.
@note
- The images must be ordered as they were an image sequence. Additionally, each frame should be as close as posible to the previous and posterior.
- For now DAISY features are used in order to compute the 2d points tracks and it only works for 3-4 images.
- To see a working example for scene reconstruction, check the following tutorial: @ref tutorial_sfm_scene_reconstruction.
*/
CV_EXPORTS
void
reconstruct(const std::vector<std::string> images, OutputArray Rs, OutputArray Ts,
InputOutputArray K, OutputArray points3d, bool is_projective = false);
#endif /* CV_DOXYGEN || CERES_FOUND */
//! @} sfm
} /* namespace cv */
} /* namespace sfm */
#endif
/* End of file. */
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, Willow Garage, Inc.
* 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 Willow Garage, Inc. 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 OWNER 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.
*
*/
#ifndef __OPENCV_SFM_ROBUST_HPP__
#define __OPENCV_SFM_ROBUST_HPP__
#ifdef __cplusplus
#include <opencv2/core.hpp>
namespace cv
{
namespace sfm
{
//! @addtogroup robust
//! @{
/** @brief Estimate robustly the fundamental matrix between two dataset of 2D point (image coords space).
@param x1 Input 2xN Array of 2D points in view 1.
@param x2 Input 2xN Array of 2D points in view 2.
@param max_error maximum error (in pixels).
@param F Output 3x3 fundamental matrix such that \f$x_2^T F x_1=0\f$.
@param inliers Output 1xN vector that contains the indexes of the detected inliers.
@param outliers_probability outliers probability (in ]0,1[).
The number of iterations is controlled using the following equation:
\f$k = \frac{log(1-p)}{log(1.0 - w^n )}\f$ where \f$k\f$, \f$w\f$ and \f$n\f$ are the number of
iterations, the inliers ratio and minimun number of selected independent samples.
The more this value is high, the less the function selects ramdom samples.
The fundamental solver relies on the 8 point solution. Returns the best error (in pixels), associated to the solution F.
*/
CV_EXPORTS
double
fundamentalFromCorrespondences8PointRobust( InputArray x1,
InputArray x2,
double max_error,
OutputArray F,
OutputArray inliers,
double outliers_probability = 1e-2 );
/** @brief Estimate robustly the fundamental matrix between two dataset of 2D point (image coords space).
@param x1 Input 2xN Array of 2D points in view 1.
@param x2 Input 2xN Array of 2D points in view 2.
@param max_error maximum error (in pixels).
@param F Output 3x3 fundamental matrix such that \f$x_2^T F x_1=0\f$.
@param inliers Output 1xN vector that contains the indexes of the detected inliers.
@param outliers_probability outliers probability (in ]0,1[).
The number of iterations is controlled using the following equation:
\f$k = \frac{log(1-p)}{log(1.0 - w^n )}\f$ where \f$k\f$, \f$w\f$ and \f$n\f$ are the number of
iterations, the inliers ratio and minimun number of selected independent samples.
The more this value is high, the less the function selects ramdom samples.
The fundamental solver relies on the 7 point solution. Returns the best error (in pixels), associated to the solution F.
*/
CV_EXPORTS
double
fundamentalFromCorrespondences7PointRobust( InputArray x1,
InputArray x2,
double max_error,
OutputArray F,
OutputArray inliers,
double outliers_probability = 1e-2 );
//! @} sfm
} /* namespace cv */
} /* namespace sfm */
#endif /* __cplusplus */
#endif
/* End of file. */
\ No newline at end of file
This diff is collapsed.
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, Willow Garage, Inc.
* 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 Willow Garage, Inc. 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 OWNER 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.
*
*/
#ifndef __OPENCV_SFM_TRIANGULATION_HPP__
#define __OPENCV_SFM_TRIANGULATION_HPP__
#include <opencv2/core.hpp>
namespace cv
{
namespace sfm
{
//! @addtogroup triangulation
//! @{
/** @brief Reconstructs bunch of points by triangulation.
@param points2d Input vector of vectors of 2d points (the inner vector is per image). Has to be 2 X N.
@param projection_matrices Input vector with 3x4 projections matrices of each image.
@param points3d Output array with computed 3d points. Is 3 x N.
Triangulates the 3d position of 2d correspondences between several images.
Reference: Internally it uses DLT method @cite HartleyZ00 12.2 pag.312
*/
CV_EXPORTS
void
triangulatePoints(InputArrayOfArrays points2d, InputArrayOfArrays projection_matrices,
OutputArray points3d);
//! @} sfm
} /* namespace sfm */
} /* namespace cv */
#endif
/* End of file. */
This diff is collapsed.
This diff is collapsed.
resized_IMG_2889.jpg
resized_IMG_2890.jpg
resized_IMG_2891.jpg
resized_IMG_2892.jpg
\ No newline at end of file
This diff is collapsed.
#include <opencv2/sfm.hpp>
#include <opencv2/core.hpp>
#include <opencv2/viz.hpp>
#include <iostream>
#include <fstream>
#include <string>
using namespace std;
using namespace cv;
using namespace cv::sfm;
static void help() {
cout
<< "\n------------------------------------------------------------------\n"
<< " This program shows the two view reconstruction capabilities in the \n"
<< " OpenCV Structure From Motion (SFM) module.\n"
<< " It uses the following data from the VGG datasets at ...\n"
<< " Usage:\n"
<< " reconv2_pts.txt \n "
<< " where the first line has the number of points and each subsequent \n"
<< " line has entries for matched points as: \n"
<< " x1 y1 x2 y2 \n"
<< "------------------------------------------------------------------\n\n"
<< endl;
}
int main(int argc, char** argv)
{
// Do projective reconstruction
bool is_projective = true;
// Read 2D points from text file
Mat_<double> x1, x2;
int npts;
if (argc < 2) {
help();
exit(0);
} else {
ifstream myfile(argv[1]);
if (!myfile.is_open()) {
cout << "Unable to read file: " << argv[1] << endl;
exit(0);
} else {
string line;
// Read number of points
getline(myfile, line);
npts = (int) atof(line.c_str());
x1 = Mat_<double>(2, npts);
x2 = Mat_<double>(2, npts);
// Read the point coordinates
for (int i = 0; i < npts; ++i) {
getline(myfile, line);
stringstream s(line);
string cord;
s >> cord;
x1(0, i) = atof(cord.c_str());
s >> cord;
x1(1, i) = atof(cord.c_str());
s >> cord;
x2(0, i) = atof(cord.c_str());
s >> cord;
x2(1, i) = atof(cord.c_str());
}
myfile.close();
}
}
// Call the reconstruction function
std::vector < Mat_<double> > points2d;
points2d.push_back(x1);
points2d.push_back(x2);
Matx33d K_estimated;
Mat_<double> points3d_estimated;
std::vector < cv::Mat > Ps_estimated;
reconstruct(points2d, Ps_estimated, points3d_estimated, K_estimated, is_projective);
// Print output
cout << endl;
cout << "Projection Matrix of View 1: " << endl;
cout << "============================ " << endl;
cout << Ps_estimated[0] << endl << endl;
cout << "Projection Matrix of View 2: " << endl;
cout << "============================ " << endl;
cout << Ps_estimated[1] << endl << endl;
// Display 3D points using VIZ module
// Create the pointcloud
std::vector<cv::Vec3f> point_cloud;
for (int i = 0; i < npts; ++i) {
cv::Vec3f point3d((float) points3d_estimated(0, i),
(float) points3d_estimated(1, i),
(float) points3d_estimated(2, i));
point_cloud.push_back(point3d);
}
// Create a 3D window
viz::Viz3d myWindow("Coordinate Frame");
/// Add coordinate axes
myWindow.showWidget("Coordinate Widget", viz::WCoordinateSystem());
viz::WCloud cloud_widget(point_cloud, viz::Color::green());
myWindow.showWidget("cloud", cloud_widget);
myWindow.spin();
return 0;
}
\ No newline at end of file
#include <opencv2/sfm.hpp>
#include <opencv2/viz.hpp>
#include <opencv2/calib3d.hpp>
#include <opencv2/core.hpp>
#include <iostream>
#include <fstream>
#include <string>
using namespace std;
using namespace cv;
using namespace cv::sfm;
static void help() {
cout
<< "\n------------------------------------------------------------------------------------\n"
<< " This program shows the multiview reconstruction capabilities in the \n"
<< " OpenCV Structure From Motion (SFM) module.\n"
<< " It reconstruct a scene from a set of 2D images \n"
<< " Usage:\n"
<< " example_sfm_scene_reconstruction <path_to_file> <f> <cx> <cy>\n"
<< " where: path_to_file is the file absolute path into your system which contains\n"
<< " the list of images to use for reconstruction. \n"
<< " f is the focal lenght in pixels. \n"
<< " cx is the image principal point x coordinates in pixels. \n"
<< " cy is the image principal point y coordinates in pixels. \n"
<< "------------------------------------------------------------------------------------\n\n"
<< endl;
}
int getdir(const string _filename, vector<string> &files)
{
ifstream myfile(_filename.c_str());
if (!myfile.is_open()) {
cout << "Unable to read file: " << _filename << endl;
exit(0);
} else {;
size_t found = _filename.find_last_of("/\\");
string line_str, path_to_file = _filename.substr(0, found);
while ( getline(myfile, line_str) )
files.push_back(path_to_file+string("/")+line_str);
}
return 1;
}
int main(int argc, char* argv[])
{
// Read input parameters
if ( argc != 5 )
{
help();
exit(0);
}
// Parse the image paths
vector<string> images_paths;
getdir( argv[1], images_paths );
// Build instrinsics
float f = atof(argv[2]),
cx = atof(argv[3]), cy = atof(argv[4]);
Matx33d K = Matx33d( f, 0, cx,
0, f, cy,
0, 0, 1);
/// Reconstruct the scene using the 2d images
bool is_projective = true;
vector<Mat> Rs_est, ts_est, points3d_estimated;
reconstruct(images_paths, Rs_est, ts_est, K, points3d_estimated, is_projective);
// Print output
cout << "\n----------------------------\n" << endl;
cout << "Reconstruction: " << endl;
cout << "============================" << endl;
cout << "Estimated 3D points: " << points3d_estimated.size() << endl;
cout << "Estimated cameras: " << Rs_est.size() << endl;
cout << "Refined intrinsics: " << endl << K << endl << endl;
cout << "3D Visualization: " << endl;
cout << "============================" << endl;
/// Create 3D windows
viz::Viz3d window("Coordinate Frame");
window.setWindowSize(Size(500,500));
window.setWindowPosition(Point(150,150));
window.setBackgroundColor(); // black by default
// Create the pointcloud
cout << "Recovering points ... ";
// recover estimated points3d
vector<Vec3f> point_cloud_est;
for (int i = 0; i < points3d_estimated.size(); ++i)
point_cloud_est.push_back(Vec3f(points3d_estimated[i]));
cout << "[DONE]" << endl;
/// Recovering cameras
cout << "Recovering cameras ... ";
vector<Affine3d> path;
for (size_t i = 0; i < Rs_est.size(); ++i)
path.push_back(Affine3d(Rs_est[i],ts_est[i]));
cout << "[DONE]" << endl;
/// Add the pointcloud
if ( point_cloud_est.size() > 0 )
{
cout << "Rendering points ... ";
viz::WCloud cloud_widget(point_cloud_est, viz::Color::green());
window.showWidget("point_cloud", cloud_widget);
cout << "[DONE]" << endl;
}
else
{
cout << "Cannot render points: Empty pointcloud" << endl;
}
/// Add cameras
if ( path.size() > 0 )
{
cout << "Rendering Cameras ... ";
window.showWidget("cameras_frames_and_lines", viz::WTrajectory(path, viz::WTrajectory::BOTH, 0.1, viz::Color::green()));
window.showWidget("cameras_frustums", viz::WTrajectoryFrustums(path, K, 0.1, viz::Color::yellow()));
window.setViewerPose(path[0]);
cout << "[DONE]" << endl;
}
else
{
cout << "Cannot render the cameras: Empty path" << endl;
}
/// Wait for key 'q' to close the window
cout << endl << "Press 'q' to close each windows ... " << endl;
window.spin();
return 0;
}
\ No newline at end of file
#include <opencv2/core.hpp>
#include <opencv2/sfm.hpp>
#include <opencv2/viz.hpp>
#include <iostream>
#include <fstream>
#include <string>
using namespace std;
using namespace cv;
using namespace cv::sfm;
static void help() {
cout
<< "\n------------------------------------------------------------------\n"
<< " This program shows the camera trajectory reconstruction capabilities\n"
<< " in the OpenCV Structure From Motion (SFM) module.\n"
<< " \n"
<< " Usage:\n"
<< " example_sfm_trajectory_reconstruction <path_to_tracks_file> <f> <cx> <cy>\n"
<< " where: is the tracks file absolute path into your system. \n"
<< " \n"
<< " The file must have the following format: \n"
<< " row1 : x1 y1 x2 y2 ... x36 y36 for track 1\n"
<< " row2 : x1 y1 x2 y2 ... x36 y36 for track 2\n"
<< " etc\n"
<< " \n"
<< " i.e. a row gives the 2D measured position of a point as it is tracked\n"
<< " through frames 1 to 36. If there is no match found in a view then x\n"
<< " and y are -1.\n"
<< " \n"
<< " Each row corresponds to a different point.\n"
<< " \n"
<< " f is the focal lenght in pixels. \n"
<< " cx is the image principal point x coordinates in pixels. \n"
<< " cy is the image principal point y coordinates in pixels. \n"
<< "------------------------------------------------------------------\n\n"
<< endl;
}
/* Build the following structure data
*
* frame1 frame2 frameN
* track1 | (x11,y11) | -> | (x12,y12) | -> | (x1N,y1N) |
* track2 | (x21,y11) | -> | (x22,y22) | -> | (x2N,y2N) |
* trackN | (xN1,yN1) | -> | (xN2,yN2) | -> | (xNN,yNN) |
*
*
* In case a marker (x,y) does not appear in a frame its
* values will be (-1,-1).
*/
void
parser_2D_tracks(const string &_filename, std::vector<Mat> &points2d )
{
ifstream myfile(_filename.c_str());
if (!myfile.is_open())
{
cout << "Unable to read file: " << _filename << endl;
exit(0);
} else {
double x, y;
string line_str;
int n_frames = 0, n_tracks = 0;
// extract data from text file
vector<vector<Vec2d> > tracks;
for ( ; getline(myfile,line_str); ++n_tracks)
{
istringstream line(line_str);
vector<Vec2d> track;
for ( n_frames = 0; line >> x >> y; ++n_frames)
{
if ( x > 0 && y > 0)
track.push_back(Vec2d(x,y));
else
track.push_back(Vec2d(-1));
}
tracks.push_back(track);
}
// embed data in reconstruction api format
for (int i = 0; i < n_frames; ++i)
{
Mat_<double> frame(2, n_tracks);
for (int j = 0; j < n_tracks; ++j)
{
frame(0,j) = tracks[j][i][0];
frame(1,j) = tracks[j][i][1];
}
points2d.push_back(Mat(frame));
}
myfile.close();
}
}
/* Keyboard callback to control 3D visualization
*/
bool camera_pov = false;
void keyboard_callback(const viz::KeyboardEvent &event, void* cookie)
{
if ( event.action == 0 &&!event.symbol.compare("s") )
camera_pov = !camera_pov;
}
/* Sample main code
*/
int main(int argc, char** argv)
{
// Read input parameters
if ( argc != 5 )
{
help();
exit(0);
}
// Read 2D points from text file
std::vector<Mat> points2d;
parser_2D_tracks( argv[1], points2d );
// Set the camera calibration matrix
const double f = atof(argv[2]),
cx = atof(argv[3]), cy = atof(argv[4]);
Matx33d K = Matx33d( f, 0, cx,
0, f, cy,
0, 0, 1);
/// Reconstruct the scene using the 2d correspondences
bool is_projective = true;
vector<Mat> Rs_est, ts_est, points3d_estimated;
reconstruct(points2d, Rs_est, ts_est, K, points3d_estimated, is_projective);
// Print output
cout << "\n----------------------------\n" << endl;
cout << "Reconstruction: " << endl;
cout << "============================" << endl;
cout << "Estimated 3D points: " << points3d_estimated.size() << endl;
cout << "Estimated cameras: " << Rs_est.size() << endl;
cout << "Refined intrinsics: " << endl << K << endl << endl;
cout << "3D Visualization: " << endl;
cout << "============================" << endl;
/// Create 3D windows
viz::Viz3d window_est("Estimation Coordinate Frame");
window_est.setBackgroundColor(); // black by default
window_est.registerKeyboardCallback(&keyboard_callback);
// Create the pointcloud
cout << "Recovering points ... ";
// recover estimated points3d
vector<Vec3f> point_cloud_est;
for (int i = 0; i < points3d_estimated.size(); ++i)
point_cloud_est.push_back(Vec3f(points3d_estimated[i]));
cout << "[DONE]" << endl;
/// Recovering cameras
cout << "Recovering cameras ... ";
vector<Affine3d> path_est;
for (size_t i = 0; i < Rs_est.size(); ++i)
path_est.push_back(Affine3d(Rs_est[i],ts_est[i]));
cout << "[DONE]" << endl;
/// Add cameras
cout << "Rendering Trajectory ... ";
/// Wait for key 'q' to close the window
cout << endl << "Press: " << endl;
cout << " 's' to switch the camera pov" << endl;
cout << " 'q' to close the windows " << endl;
if ( path_est.size() > 0 )
{
// animated trajectory
int idx = 0, forw = -1, n = static_cast<int>(path_est.size());
while(!window_est.wasStopped())
{
/// Render points as 3D cubes
for (size_t i = 0; i < point_cloud_est.size(); ++i)
{
Vec3d point = point_cloud_est[i];
Affine3d point_pose(Mat::eye(3,3,CV_64F), point);
char buffer[50];
sprintf (buffer, "%d", static_cast<int>(i));
viz::WCube cube_widget(Point3f(0.1,0.1,0.0), Point3f(0.0,0.0,-0.1), true, viz::Color::blue());
cube_widget.setRenderingProperty(viz::LINE_WIDTH, 2.0);
window_est.showWidget("Cube"+string(buffer), cube_widget, point_pose);
}
Affine3d cam_pose = path_est[idx];
viz::WCameraPosition cpw(0.25); // Coordinate axes
viz::WCameraPosition cpw_frustum(K, 0.3, viz::Color::yellow()); // Camera frustum
if ( camera_pov )
window_est.setViewerPose(cam_pose);
else
{
// render complete trajectory
window_est.showWidget("cameras_frames_and_lines_est", viz::WTrajectory(path_est, viz::WTrajectory::PATH, 1.0, viz::Color::green()));
window_est.showWidget("CPW", cpw, cam_pose);
window_est.showWidget("CPW_FRUSTUM", cpw_frustum, cam_pose);
}
// update trajectory index (spring effect)
forw *= (idx==n || idx==0) ? -1: 1; idx += forw;
// frame rate 1s
window_est.spinOnce(1, true);
window_est.removeAllWidgets();
}
}
return 0;
}
/*
* Software License Agreement (BSD License)
*
* Copyright (c) 2009, Willow Garage, Inc.
* 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 Willow Garage, Inc. 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 OWNER 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.
*
*/
#include "precomp.hpp"
// Eigen
#include <Eigen/Core>
// OpenCV
#include <opencv2/core/eigen.hpp>
#include <opencv2/sfm/conditioning.hpp>
// libmv headers
#include "libmv/multiview/conditioning.h"
namespace cv
{
namespace sfm
{
template<typename T>
void
preconditionerFromPoints( const Mat_<T> &_points,
Mat_<T> _Tr )
{
libmv::Mat points;
libmv::Mat3 Tr;
cv2eigen( _points, points );
libmv::PreconditionerFromPoints( points, &Tr );
eigen2cv( Tr, _Tr );
}
void
preconditionerFromPoints( InputArray _points,
OutputArray _T )
{
const Mat points = _points.getMat();
const int depth = points.depth();
CV_Assert((points.dims == 2 || points.dims == 3) && (depth == CV_32F || depth == CV_64F));
_T.create(3, 3, depth);
Mat T = _T.getMat();
if ( depth == CV_32F )
{
preconditionerFromPoints<float>(points, T);
}
else
{
preconditionerFromPoints<double>(points, T);
}
}
template<typename T>
void
isotropicPreconditionerFromPoints( const Mat_<T> &_points,
Mat_<T> _T )
{
libmv::Mat points;
libmv::Mat3 Tr;
cv2eigen( _points, points );
libmv::IsotropicPreconditionerFromPoints( points, &Tr );
eigen2cv( Tr, _T );
}
void
isotropicPreconditionerFromPoints( InputArray _points,
OutputArray _T )
{
const Mat points = _points.getMat();
const int depth = points.depth();
CV_Assert((points.dims == 2 || points.dims == 3) && (depth == CV_32F || depth == CV_64F));
_T.create(3, 3, depth);
Mat T = _T.getMat();
if ( depth == CV_32F )
{
isotropicPreconditionerFromPoints<float>(points, T);
}
else
{
isotropicPreconditionerFromPoints<double>(points, T);
}
}
template<typename T>
void
applyTransformationToPoints( const Mat_<T> &_points,
const Mat_<T> &_T,
Mat_<T> _transformed_points )
{
libmv::Mat points, transformed_points;
libmv::Mat3 Tr;
cv2eigen( _points, points );
cv2eigen( _T, Tr );
libmv::ApplyTransformationToPoints( points, Tr, &transformed_points );
eigen2cv( transformed_points, _transformed_points );
}
void
applyTransformationToPoints( InputArray _points,
InputArray _T,
OutputArray _transformed_points )
{
const Mat points = _points.getMat(), T = _T.getMat();
const int depth = points.depth();
CV_Assert((points.dims == 2 || points.dims == 3) && T.size() == Size(3,3) && (depth == CV_32F || depth == CV_64F));
_transformed_points.create(points.size(), depth);
Mat transformed_points = _transformed_points.getMat();
if ( depth == CV_32F )
{
applyTransformationToPoints<float>(points, T, transformed_points);
}
else
{
applyTransformationToPoints<double>(points, T, transformed_points);
}
}
void
normalizePoints( InputArray points,
OutputArray normalized_points,
OutputArray T )
{
preconditionerFromPoints(points, T);
applyTransformationToPoints(points, T, normalized_points);
}
void
normalizeIsotropicPoints( InputArray points,
OutputArray normalized_points,
OutputArray T )
{
isotropicPreconditionerFromPoints(points, T);
applyTransformationToPoints(points, T, normalized_points);
}
} /* namespace sfm */
} /* namespace cv */
This diff is collapsed.
This diff is collapsed.
#Install macro for libmv libraries
MACRO (LIBMV_INSTALL_LIB name)
set_target_properties( ${name}
PROPERTIES
ARCHIVE_OUTPUT_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/lib
)
ENDMACRO (LIBMV_INSTALL_LIB)
\ No newline at end of file
# installation rules
include(CMake/Installation.cmake)
set(BUILD_SHARED_LIBS OFF) # Force static libs for 3rdparty dependencies
add_subdirectory(libmv)
\ No newline at end of file
add_subdirectory(correspondence)
add_subdirectory(multiview)
add_subdirectory(numeric)
if ( Ceres_FOUND )
add_subdirectory(simple_pipeline)
endif ()
\ No newline at end of file
# define the source files
SET(BASE_SRC )
# define the header files (make the headers appear in IDEs.)
FILE(GLOB BASE_HDRS *.h)
ADD_LIBRARY(base STATIC ${BASE_SRC} ${BASE_HDRS})
LIBMV_INSTALL_LIB(base)
\ No newline at end of file
// Copyright (c) 2007, 2008 libmv authors.
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to
// deal in the Software without restriction, including without limitation the
// rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
// sell copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
// IN THE SOFTWARE.
//
// Get an aligned vector implementation. Must be included before <vector>. The
// Eigen guys went through some trouble to make a portable override for the
// fixed size vector types.
#ifndef LIBMV_BASE_VECTOR_H
#define LIBMV_BASE_VECTOR_H
#include <cstring>
#include <new>
#include <Eigen/Core>
namespace libmv {
// A simple container class, which guarantees 16 byte alignment needed for most
// vectorization. Don't use this container for classes that cannot be copied
// via memcpy.
// FIXME: this class has some issues:
// - doesn't support iterators.
// - impede compatibility with code using STL.
// - the STL already provide support for custom allocators
// it could be replaced with a simple
// template <T> class vector : std::vector<T, aligned_allocator> {} declaration
// provided it doesn't break code relying on libmv::vector specific behavior
template <typename T,
typename Allocator = Eigen::aligned_allocator<T> >
class vector {
public:
~vector() { clear(); }
vector() { init(); }
vector(int size) { init(); resize(size); }
vector(int size, const T & val) {
init();
resize(size);
std::fill(data_, data_+size_, val); }
// Copy constructor and assignment.
vector(const vector<T, Allocator> &rhs) {
init();
copy(rhs);
}
vector<T, Allocator> &operator=(const vector<T, Allocator> &rhs) {
if (&rhs != this) {
copy(rhs);
}
return *this;
}
/// Swaps the contents of two vectors in constant time.
void swap(vector<T, Allocator> &other) {
std::swap(allocator_, other.allocator_);
std::swap(size_, other.size_);
std::swap(capacity_, other.capacity_);
std::swap(data_, other.data_);
}
T *data() const { return data_; }
int size() const { return size_; }
int capacity() const { return capacity_; }
const T& back() const { return data_[size_ - 1]; }
T& back() { return data_[size_ - 1]; }
const T& front() const { return data_[0]; }
T& front() { return data_[0]; }
const T& operator[](int n) const { return data_[n]; }
T& operator[](int n) { return data_[n]; }
const T& at(int n) const { return data_[n]; }
T& at(int n) { return data_[n]; }
const T * begin() const { return data_; }
const T * end() const { return data_+size_; }
T * begin() { return data_; }
T * end() { return data_+size_; }
void resize(size_t size) {
reserve(size);
if (size > size_) {
construct(size_, size);
} else if (size < size_) {
destruct(size, size_);
}
size_ = size;
}
void push_back(const T &value) {
if (size_ == capacity_) {
reserve(size_ ? 2 * size_ : 1);
}
new (&data_[size_++]) T(value);
}
void pop_back() {
resize(size_ - 1);
}
void clear() {
destruct(0, size_);
deallocate();
init();
}
void reserve(unsigned int size) {
if (size > size_) {
T *data = static_cast<T *>(allocate(size));
memcpy(data, data_, sizeof(*data)*size_);
allocator_.deallocate(data_, capacity_);
data_ = data;
capacity_ = size;
}
}
bool empty() {
return size_ == 0;
}
private:
void construct(int start, int end) {
for (int i = start; i < end; ++i) {
new (&data_[i]) T;
}
}
void destruct(int start, int end) {
for (int i = start; i < end; ++i) {
data_[i].~T();
}
}
void init() {
size_ = 0;
data_ = 0;
capacity_ = 0;
}
void *allocate(int size) {
return size ? allocator_.allocate(size) : 0;
}
void deallocate() {
allocator_.deallocate(data_, size_);
data_ = 0;
}
void copy(const vector<T, Allocator> &rhs) {
resize(rhs.size());
for (int i = 0; i < rhs.size(); ++i) {
(*this)[i] = rhs[i];
}
}
Allocator allocator_;
size_t size_;
size_t capacity_;
T *data_;
};
} // namespace libmv
#endif // LIBMV_BASE_VECTOR_H
// Copyright (c) 2009 libmv authors.
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to
// deal in the Software without restriction, including without limitation the
// rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
// sell copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
// IN THE SOFTWARE.
#ifndef LIBMV_BASE_VECTOR_UTILS_H_
#define LIBMV_BASE_VECTOR_UTILS_H_
/// Delete the contents of a container.
template <class Array>
void DeleteElements(Array *array) {
for (int i = 0; i < array->size(); ++i) {
delete (*array)[i];
}
array->clear();
}
#endif // LIBMV_BASE_VECTOR_UTILS_H_
# define the source files
SET(CORRESPONDENCE_SRC feature_matching.cc
matches.cc
nRobustViewMatching.cc)
# define the header files (make the headers appear in IDEs.)
FILE(GLOB CORRESPONDENCE_HDRS *.h)
ADD_LIBRARY(correspondence STATIC ${CORRESPONDENCE_SRC} ${CORRESPONDENCE_HDRS})
TARGET_LINK_LIBRARIES(correspondence multiview)
LIBMV_INSTALL_LIB(correspondence)
\ No newline at end of file
// Copyright (c) 2009 libmv authors.
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to
// deal in the Software without restriction, including without limitation the
// rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
// sell copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
// IN THE SOFTWARE.
#ifndef LIBMV_CORRESPONDENCE_INT_BIPARTITE_GRAPH_H_
#define LIBMV_CORRESPONDENCE_INT_BIPARTITE_GRAPH_H_
#include <limits>
#include <map>
#include <set>
#include <cassert>
namespace libmv {
// A bipartite graph with labelled edges.
template<typename T, typename EdgeT>
class BipartiteGraph {
public:
typedef std::map<std::pair<T, T>, EdgeT> EdgeMap;
void Insert(const T &left, const T &right, const EdgeT &edge) {
left_to_right_[std::make_pair(left, right)] = edge;
right_to_left_[std::make_pair(right, left)] = edge;
}
void Remove(const T &left, const T &right) {
typename EdgeMap::iterator iter =
left_to_right_.find(std::make_pair(left, right));
if (iter != left_to_right_.end())
left_to_right_.erase(iter);
iter = right_to_left_.find(std::make_pair(right, left));
if (iter != right_to_left_.end())
right_to_left_.erase(iter);
}
int NumLeftLeft(T left) const {
int n = 0;
typename EdgeMap::const_iterator it;
for (it = left_to_right_.begin(); it != left_to_right_.end(); ++it) {
if (it->first.first == left)
n++;
}
return n;
}
int NumLeftRight(T right) const {
int n = 0;
typename EdgeMap::const_iterator it;
for (it = left_to_right_.begin(); it != left_to_right_.end(); ++it) {
if (it->first.second == right)
n++;
}
return n;
}
// Erases all the elements.
// Note that this function does not desallocate pointers
void Clear() {
left_to_right_.clear();
right_to_left_.clear();
}
class Range {
friend class BipartiteGraph<T, EdgeT>;
public:
T left() const { return reversed_ ? it_->first.second : it_->first.first; }
T right() const { return reversed_ ? it_->first.first : it_->first.second;}
EdgeT edge() const { return it_->second; }
void operator++() { ++it_; }
EdgeT operator*() { return it_->second; }
operator bool() const { return it_ != end_; }
private:
Range(typename EdgeMap::const_iterator it,
typename EdgeMap::const_iterator end,
bool reversed)
: reversed_(reversed), it_(it), end_(end) {}
bool reversed_;
typename EdgeMap::const_iterator it_, end_;
};
Range All() const {
return Range(left_to_right_.begin(), left_to_right_.end(), false);
}
Range AllReversed() const {
return Range(right_to_left_.begin(), right_to_left_.end(), true);
}
Range ToLeft(T left) const {
return Range(left_to_right_.lower_bound(Lower(left)),
left_to_right_.upper_bound(Upper(left)), false);
}
Range ToRight(T right) const {
return Range(right_to_left_.lower_bound(Lower(right)),
right_to_left_.upper_bound(Upper(right)), true);
}
// Find a pointer to the edge, or NULL if not found.
const EdgeT *Edge(T left, T right) const {
typename EdgeMap::const_iterator it =
left_to_right_.find(std::make_pair(left, right));
if (it != left_to_right_.end()) {
return &(it->second);
}
return NULL;
}
private:
std::pair<T, T> Lower(T first) const {
return std::make_pair(first, std::numeric_limits<T>::min());
}
std::pair<T, T> Upper(T first) const {
return std::make_pair(first, std::numeric_limits<T>::max());
}
EdgeMap left_to_right_;
EdgeMap right_to_left_;
};
} // namespace libmv
#endif // LIBMV_CORRESPONDENCE_BIPARTITE_GRAPH_H_
// Copyright (c) 2007, 2008 libmv authors.
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to
// deal in the Software without restriction, including without limitation the
// rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
// sell copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
// IN THE SOFTWARE.
#ifndef LIBMV_CORRESPONDENCE_FEATURE_H_
#define LIBMV_CORRESPONDENCE_FEATURE_H_
#include <opencv2/core.hpp>
#include "libmv/numeric/numeric.h"
namespace libmv
{
class Feature
{
public:
virtual
~Feature() {};
};
class PointFeature : public Feature {
public:
PointFeature(float xx=0.0f, float yy=0.0f) {
coords[0] = xx;
coords[1] = yy;
scale = 0.0;
orientation = 0.0;
}
PointFeature &operator=(const PointFeature &other)
{
if (this == &other)
return *this;
scale = other.scale;
orientation = other.orientation;
coords = other.coords;
return *this;
}
PointFeature(const cv::KeyPoint & keypoint) {
coords[0] = keypoint.pt.x;
coords[1] = keypoint.pt.y;
scale = keypoint.octave;
orientation = keypoint.angle;
}
float x() const { return coords(0); }
float y() const { return coords(1); }
Vec2f coords; // (x, y), i.e. (column, row).
float scale; // In pixels.
float orientation; // In radians.
};
} // namespace libmv
#endif // LIBMV_CORRESPONDENCE_FEATURE_H_
// Copyright (c) 2009 libmv authors.
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to
// deal in the Software without restriction, including without limitation the
// rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
// sell copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
// IN THE SOFTWARE.
#include <opencv2/features2d.hpp>
#include "libmv/correspondence/feature_matching.h"
// Compute candidate matches between 2 sets of features. Two features A and B
// are a candidate match if A is the nearest neighbor of B and B is the nearest
// neighbor of A.
void FindCandidateMatches(const FeatureSet &left,
const FeatureSet &right,
Matches *matches) {
if (left.features.empty() ||
right.features.empty() ) {
return;
}
cv::FlannBasedMatcher matcherA;
cv::FlannBasedMatcher matcherB;
// Paste the necessary data in contiguous arrays.
cv::Mat arrayA = FeatureSet::FeatureSetDescriptorsToContiguousArray(left);
cv::Mat arrayB = FeatureSet::FeatureSetDescriptorsToContiguousArray(right);
matcherA.add(std::vector<cv::Mat>(1, arrayB));
matcherB.add(std::vector<cv::Mat>(1, arrayA));
std::vector<cv::DMatch> matchesA, matchesB;
matcherA.match(arrayA, matchesA);
matcherB.match(arrayB, matchesB);
// From putative matches get symmetric matches.
int max_track_number = 0;
for (size_t i = 0; i < matchesA.size(); ++i)
{
// Add the match only if we have a symmetric result.
if (i == matchesB[matchesA[i].trainIdx].trainIdx)
{
matches->Insert(0, max_track_number, &left.features[i]);
matches->Insert(1, max_track_number, &right.features[matchesA[i].trainIdx]);
++max_track_number;
}
}
}
cv::Mat FeatureSet::FeatureSetDescriptorsToContiguousArray
( const FeatureSet & featureSet ) {
if (featureSet.features.empty()) {
return cv::Mat();
}
int descriptorSize = featureSet.features[0].descriptor.cols;
// Allocate and paste the necessary data.
cv::Mat array(featureSet.features.size(), descriptorSize, CV_32F);
//-- Paste data in the contiguous array :
for (int i = 0; i < (int)featureSet.features.size(); ++i) {
featureSet.features[i].descriptor.copyTo(array.row(i));
}
return array;
}
// Compute candidate matches between 2 sets of features with a ratio.
void FindCandidateMatches_Ratio(const FeatureSet &left,
const FeatureSet &right,
Matches *matches,
float fRatio) {
if (left.features.empty() || right.features.empty())
return;
cv::FlannBasedMatcher matcherA;
// Paste the necessary data in contiguous arrays.
cv::Mat arrayA = FeatureSet::FeatureSetDescriptorsToContiguousArray(left);
cv::Mat arrayB = FeatureSet::FeatureSetDescriptorsToContiguousArray(right);
matcherA.add(std::vector<cv::Mat>(1, arrayB));
std::vector < std::vector<cv::DMatch> > matchesA;
matcherA.knnMatch(arrayA, matchesA, 2);
// From putative matches get matches that fit the "Ratio" heuristic.
int max_track_number = 0;
for (size_t i = 0; i < matchesA.size(); ++i)
{
float distance0 = matchesA[i][0].distance;
float distance1 = matchesA[i][1].distance;
// Add the match only if we have a symmetric result.
if (distance0 < fRatio * distance1)
{
{
matches->Insert(0, max_track_number, &left.features[i]);
matches->Insert(1, max_track_number, &right.features[matchesA[i][0].trainIdx]);
++max_track_number;
}
}
}
}
// Compute correspondences that match between 2 sets of features with a ratio.
void FindCorrespondences(const FeatureSet &left,
const FeatureSet &right,
std::map<size_t, size_t> *correspondences,
float fRatio) {
if (left.features.empty() || right.features.empty())
return;
cv::FlannBasedMatcher matcherA;
// Paste the necessary data in contiguous arrays.
cv::Mat arrayA = FeatureSet::FeatureSetDescriptorsToContiguousArray(left);
cv::Mat arrayB = FeatureSet::FeatureSetDescriptorsToContiguousArray(right);
matcherA.add(std::vector<cv::Mat>(1, arrayB));
std::vector < std::vector<cv::DMatch> > matchesA;
matcherA.knnMatch(arrayA, matchesA, 2);
// From putative matches get matches that fit the "Ratio" heuristic.
for (size_t i = 0; i < matchesA.size(); ++i)
{
float distance0 = matchesA[i][0].distance;
float distance1 = matchesA[i][1].distance;
// Add the match only if we have a symmetric result.
if (distance0 < fRatio * distance1)
(*correspondences)[i] = matchesA[i][0].trainIdx;
}
}
// Copyright (c) 2009 libmv authors.
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to
// deal in the Software without restriction, including without limitation the
// rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
// sell copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
// IN THE SOFTWARE.
#ifndef LIBMV_CORRESPONDENCE_FEATURE_MATCHING_H_
#define LIBMV_CORRESPONDENCE_FEATURE_MATCHING_H_
#include <iostream>
#include <opencv2/core.hpp>
#include "libmv/base/vector.h"
#include "libmv/correspondence/feature.h"
#include "libmv/correspondence/matches.h"
using namespace libmv;
/// Define the description of a feature described by :
/// A PointFeature (x,y,scale,orientation),
/// And a descriptor (a vector of floats).
class KeypointFeature : public ::PointFeature {
public:
virtual ~KeypointFeature(){};
void set(const PointFeature &feature,const cv::Mat &descriptor)
{
PointFeature::operator=(feature);
descriptor.copyTo(this->descriptor);
}
// Match kdtree traits: with this, the Feature can act as a kdtree point.
float operator[](int i) const {
if (descriptor.depth() != CV_32F)
std::cerr << "KeypointFeature does not contain floats" << std::endl;
return descriptor.at<float>(i);
}
cv::Mat descriptor;
};
/// FeatureSet : Store an array of KeypointFeature ( Keypoint and descriptor).
struct FeatureSet {
std::vector<KeypointFeature> features;
/// return a float * containing the concatenation of descriptor data.
/// Must be deleted with []
static cv::Mat FeatureSetDescriptorsToContiguousArray
( const FeatureSet & featureSet );
};
// Compute candidate matches between 2 sets of features. Two features a and b
// are a candidate match if a is the nearest neighbor of b and b is the nearest
// neighbor of a.
void FindCandidateMatches(const FeatureSet &left,
const FeatureSet &right,
Matches *matches);
// Compute candidate matches between 2 sets of features.
// Keep only strong and distinctive matches by using the Davide Lowe's ratio
// method.
// I.E: A match is considered as strong if the following test is true :
// I.E distance[0] < fRatio * distances[1].
// From David Lowe “Distinctive Image Features from Scale-Invariant Keypoints”.
// You can use David Lowe's magic ratio (0.6 or 0.8).
// 0.8 allow to remove 90% of the false matches while discarding less than 5%
// of the correct matches.
void FindCandidateMatches_Ratio(const FeatureSet &left,
const FeatureSet &right,
Matches *matches,
float fRatio = 0.8f);
// TODO(pmoulon) Add Lowe's ratio symmetric match method.
// Compute correspondences that match between 2 sets of features with a ratio.
void FindCorrespondences(const FeatureSet &left,
const FeatureSet &right,
std::map<size_t, size_t> *correspondences,
float fRatio = 0.8f);
#endif //LIBMV_CORRESPONDENCE_FEATURE_MATCHING_H_
// Copyright (c) 2007, 2008 libmv authors.
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to
// deal in the Software without restriction, including without limitation the
// rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
// sell copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
// IN THE SOFTWARE.
#include "libmv/correspondence/matches.h"
#include "libmv/correspondence/feature.h"
namespace libmv {
Matches::~Matches() {}
void DeleteMatchFeatures(Matches *matches) {
(void) matches;
// XXX
/*
for (Correspondences::FeatureIterator it = correspondences->ScanAllFeatures();
!it.Done(); it.Next()) {
delete const_cast<Feature *>(it.feature());
}
*/
}
int Matches::GetNumberOfMatches(ImageID id1,ImageID id2) const
{
Features<Feature> features1 = InImage<Feature>(id1);
Features<Feature> features2 = InImage<Feature>(id2);
int count = 0;
for(int i1=0;features1;++features1,++i1)
{
Features<Feature> temp = features2;
for(int i2=0;temp;++temp,++i2)
{
if(features1.track() == temp.track())
{
++count;
break;
}
}
}
return count;
}
void Matches::DrawMatches(ImageID image_id1,const cv::Mat &image1,ImageID image_id2,const cv::Mat &image2, cv::Mat &out)const
{
std::vector<cv::KeyPoint> points1;
std::vector<cv::KeyPoint> points2;
std::vector<cv::DMatch> matches;
KeyPoints(image_id1,points1);
KeyPoints(image_id2,points2);
MatchesTwo(image_id1,image_id2,matches);
cv::drawMatches(image1,points1,image2,points2,matches,out);
}
void Matches::MatchesTwo(ImageID image1,ImageID image2,std::vector<cv::DMatch> &matches)const
{
Features<PointFeature> features1 = InImage<PointFeature>(image1);
Features<PointFeature> features2 = InImage<PointFeature>(image2);
for(int i1=0;features1;++features1,++i1)
{
Features<PointFeature> temp = features2;
for(int i2=0;temp;++temp,++i2)
{
if(features1.track() == temp.track())
{
matches.push_back(cv::DMatch(i1,i2,std::numeric_limits<float>::max()));
break;
}
}
}
}
void Matches::KeyPoints(ImageID image,std::vector<cv::KeyPoint> &keypoints)const
{
PointFeatures2KeyPoints(InImage<PointFeature>(image),keypoints);
}
void Matches::PointFeatures2KeyPoints(Features<PointFeature> features,std::vector<cv::KeyPoint> &keypoints)const
{
for(;features;++features)
keypoints.push_back(cv::KeyPoint(features.feature()->x(),features.feature()->y(),1));
}
} // namespace libmv
This diff is collapsed.
// Copyright (c) 2010 libmv authors.
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to
// deal in the Software without restriction, including without limitation the
// rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
// sell copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
// IN THE SOFTWARE.
#ifndef LIBMV_CORRESPONDENCE_N_ROBUST_VIEW_MATCHING_INTERFACE_H_
#define LIBMV_CORRESPONDENCE_N_ROBUST_VIEW_MATCHING_INTERFACE_H_
struct FeatureSet;
#include <map>
#include "libmv/correspondence/feature.h"
#include "libmv/correspondence/matches.h"
#include "libmv/correspondence/nViewMatchingInterface.h"
namespace libmv {
namespace correspondence {
using namespace std;
class nRobustViewMatching :public nViewMatchingInterface {
public:
nRobustViewMatching();
// Constructor (Specify a detector and a describer interface)
// The class do not handle memory management over this two parameter.
nRobustViewMatching(cv::Ptr<cv::FeatureDetector> pDetector,
cv::Ptr<cv::DescriptorExtractor> pDescriber);
//TODO(pmoulon) Add a constructor with a Detector and a Descriptor
// Add also a Template function to make the match robust..
~nRobustViewMatching(){};
/**
* Compute the data and store it in the class map<string,T>
*
* \param[in] filename The file from which the data will be extracted.
*
* \return True if success.
*/
bool computeData(const string & filename);
/**
* Compute the putative match between data computed from element A and B
* Store the match data internally in the class
* map< <string, string> , MatchObject >
*
* \param[in] The name of the filename A (use computed data for this element)
* \param[in] The name of the filename B (use computed data for this element)
*
* \return True if success.
*/
bool MatchData(const string & dataA, const string & dataB);
/**
* From a series of element it computes the cross putative match list.
*
* \param[in] vec_data The data on which we want compute cross matches.
*
* \return True if success (and any matches was found).
*/
bool computeCrossMatch( const std::vector<string> & vec_data);
/**
* From a series of element it computes the incremental putative match list.
* (only locally, in the relative neighborhood)
*
* \param[in] vec_data The data on which we want compute matches.
*
* \return True if success (and any matches was found).
*/
bool computeRelativeMatch( const std::vector<string> & vec_data);
/**
* Give the posibility to constrain the matches list.
*
* \param[in] matchIn The input match data between indexA and indexB.
* \param[in] dataAindex The reference index for element A.
* \param[in] dataBindex The reference index for element B.
* \param[out] matchesOut The output match that satisfy the internal constraint.
*
* \return True if success.
*/
bool computeConstrainMatches(const Matches & matchIn,
int dataAindex,
int dataBindex,
Matches * matchesOut);
/// Return pairwise correspondence ( geometrically filtered )
const map< pair<string,string>, Matches> & getSharedData() const
{ return m_sharedData; }
/// Return extracted feature over the given image.
const map<string,FeatureSet> & getViewData() const
{ return m_ViewData; }
/// Return detected geometrical consistent matches
const Matches & getMatches() const
{ return m_tracks; }
private :
/// Input data names
std::vector<string> m_vec_InputNames;
/// Data that represent each named element.
map<string,FeatureSet> m_ViewData;
/// Matches between element named element <A,B>.
map< pair<string,string>, Matches> m_sharedData;
/// LookUpTable to make the crossCorrespondence easier between tracks
/// and feature.
map<const Feature*, int> m_featureToTrackTable;
/// Matches between all the view.
Matches m_tracks;
/// Interface to detect Keypoint.
cv::Ptr<cv::FeatureDetector> m_pDetector;
/// Interface to describe Keypoint.
cv::Ptr<cv::DescriptorExtractor> m_pDescriber;
};
} // using namespace correspondence
} // using namespace libmv
#endif // LIBMV_CORRESPONDENCE_N_ROBUST_VIEW_MATCHING_INTERFACE_H_
// Copyright (c) 2010 libmv authors.
//
// Permission is hereby granted, free of charge, to any person obtaining a copy
// of this software and associated documentation files (the "Software"), to
// deal in the Software without restriction, including without limitation the
// rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
// sell copies of the Software, and to permit persons to whom the Software is
// furnished to do so, subject to the following conditions:
//
// The above copyright notice and this permission notice shall be included in
// all copies or substantial portions of the Software.
//
// THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
// FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
// AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
// LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
// FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
// IN THE SOFTWARE.
#ifndef LIBMV_CORRESPONDENCE_N_VIEW_MATCHING_INTERFACE_H_
#define LIBMV_CORRESPONDENCE_N_VIEW_MATCHING_INTERFACE_H_
#include <string>
namespace libmv {
namespace correspondence {
using namespace std;
class nViewMatchingInterface {
public:
virtual ~nViewMatchingInterface() {};
/**
* Compute the data and store it in the class map<string,T>
*
* \param[in] filename The file from which the data will be extracted.
*
* \return True if success.
*/
virtual bool computeData(const string & filename)=0;
/**
* Compute the putative match between data computed from element A and B
* Store the match data internally in the class
* map< <string, string> , MatchObject >
*
* \param[in] The name of the filename A (use computed data for this element)
* \param[in] The name of the filename B (use computed data for this element)
*
* \return True if success.
*/
virtual bool MatchData(const string & dataA, const string & dataB)=0;
/**
* From a series of element it compute the cross putative match list.
*
* \param[in] vec_data The data on which we want compute cross matches.
*
* \return True if success (and any matches was found).
*/
virtual bool computeCrossMatch( const std::vector<string> & vec_data)=0;
};
} // using namespace correspondence
} // using namespace libmv
#endif // LIBMV_CORRESPONDENCE_N_VIEW_MATCHING_INTERFACE_H_
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
# define the source files
SET(NUMERIC_SRC numeric.cc
poly.cc)
# define the header files (make the headers appear in IDEs.)
FILE(GLOB NUMERIC_HDRS *.h)
ADD_LIBRARY(numeric STATIC ${NUMERIC_SRC} ${NUMERIC_HDRS})
TARGET_LINK_LIBRARIES(numeric)
LIBMV_INSTALL_LIB(numeric)
\ No newline at end of file
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
This diff is collapsed.
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment