Structure from motion
Several classes and functions related to structure from motion.
More...
Modules |
| Read and write intermediate files for the Bundler application. |
| Functionality to read from and write to intermediate files for the Bundler application.
Bundler is an open source application for incremental SfM visual reconstruction.
|
Functions |
QList< QVCameraPose > | globalEpipolarAdjustment (const int numIterations, const QList< QVCameraPose > &initialCameraPoses, const QVDirectedGraph< QVMatrix > &reducedMatricesGraph, const QVector< bool > &freeCameras, const double lambda=1e-3, const bool adaptativeLambda=true, const TQVSparseSolve_Method solveMethod=DEFAULT_TQVSPARSESOLVE_METHOD, const int secondLevelIterations=10) |
| Refine the camera poses using epipolar geometry constraints.
|
QList< QVCameraPose > | globalEpipolarAdjustment (const int numIterations, const QList< QVCameraPose > &initialCameraPoses, const QVDirectedGraph< QVMatrix > &reducedMatricesGraph, const double lambda=1e-3, const bool adaptativeLambda=true, const TQVSparseSolve_Method solveMethod=DEFAULT_TQVSPARSESOLVE_METHOD, const int secondLevelIterations=10) |
| Refine the camera poses using epipolar geometry constraints.
|
QList< QVCameraPose > | incrementalGEA (const int numIterations, const QList< QVCameraPose > &initialCameraPoses, const QVDirectedGraph< QVMatrix > &reducedMatricesGraph, const int numFreeCameras=1, const double lambda=1e-3, const bool adaptativeLambda=true, const TQVSparseSolve_Method solveMethod=DEFAULT_TQVSPARSESOLVE_METHOD, const int secondLevelIterations=10) |
| Incremental GEA refinement.
|
QVDirectedGraph< QVMatrix > | getReducedMatrices (const QVDirectedGraph< QList< QPointFMatching > > &pointLists, const bool normalize=true, const TGEA_decomposition_method decomposition_method=GEA_CHOLESKY_DECOMPOSITION, const bool gsl=true, const double choleskyLambda=0.0, const int minPointCorrespondences=0) |
| Gets the reduced matrices for a reconstruction.
|
QVDirectedGraph< QVMatrix > | getReducedMatrices (const QVDirectedGraph< QVector< QPointFMatching > > &pointLists, const bool normalize=true, const TGEA_decomposition_method decomposition_method=GEA_CHOLESKY_DECOMPOSITION, const bool gsl=true, const double choleskyLambda=0.0, const int minPointCorrespondences=0) |
| Gets the reduced matrices for a reconstruction from the list of point correspondences detected between each view-pair in a reconstruction.
|
QVDirectedGraph< QList
< QPointFMatching > > | getPointMatchingsLists (const QList< QHash< int, QPointF > > pointProjections, const int numCams, const int minPointCorrespondences=0) |
| Obtains the list of point correspondences detected between each view-pair in a reconstruction.
|
QVDirectedGraph< QVector
< QPointFMatching > > | getPointMatchingsListsVec (const QList< QHash< int, QPointF > > pointProjections, const int numCams, const int minPointCorrespondences=0) |
| Obtains the list of point correspondences detected between each view-pair in a reconstruction.
|
QList< QHash< int, QPointF > > | correctIntrinsics (const QList< QVMatrix > &Ks, const QList< QHash< int, QPointF > > &pointsProjections) |
| Corrects linear intrinsic calibration from a set of point projections.
|
bool | testCheirality (const QList< QVCameraPose > cameraPoses, const QList< QHash< int, QPointF > > calibratedPointsProjections) |
| Test correct camera cheirality.
|
void | invertCheirality (QList< QVCameraPose > &cameraPoses, QList< QV3DPointF > &points3D) |
| Swaps the cheirality of the camera poses and 3D points contained in a SfM reconstruction.
|
double | reconstructionError (const QList< QVCameraPose > &cameraPoses, const QList< QV3DPointF > &points3D, const QList< QHash< int, QPointF > > &pointProjections) |
| Evaluate the mean reprojection error of a reconstruction.
|
double | reconstructionError (const QList< QVCameraPose > &cameraPoses, const QList< QHash< int, QPointF > > &pointProjections) |
| Evaluate the mean reprojection error of a reconstruction.
|
double | reconstructionError (const QList< QVCameraPose > &cameraPoses, const QList< QV3DPointF > &points3D, const QList< QHash< int, QPointF > > &pointProjections, const QVector< bool > &evaluateTracking) |
| Evaluate the mean reprojection error of a pair-wise reconstruction.
|
double | reconstructionError (const QVMatrix &Rt1, const QVMatrix &Rt2, const QList< QV3DPointF > &points3D, const QVector< QPointFMatching > &matchings) |
| Evaluate the mean reprojection error of a pair-wise reconstruction.
|
QVVector | reconstructionErrorResiduals (const QList< QVCameraPose > &cameraPoses, const QList< QV3DPointF > &points3D, const QList< QHash< int, QPointF > > &pointTrackings) |
| Evaluate the residuals of a reconstruction.
|
bool | checkForNaNValues (const QList< QVCameraPose > &cameraPoses) |
| Check for NaN values in a list of camera poses.
|
bool | checkForNaNValues (const QList< QV3DPointF > &points3D) |
| Check for NaN values in a list of 3D points.
|
bool | checkForNaNValues (const QList< QHash< int, QPointF > > &pointTrackings) |
| Check for NaN values in a list of point trackings.
|
bool | linearCameraPairInitialization (const QVector< QPointFMatching > &matchings, QVMatrix &Rt1, QVMatrix &Rt2) |
| Initialize the projection matrices of two views in a reconstruction, provided a list of point matchings.
|
bool | readSfMReconstruction (const QString &path, QList< QVMatrix > &cameraCalibrations, QList< QVCameraPose > &cameraPoses, QList< QV3DPointF > &points3D, QList< QHash< int, QPointF > > &pointsProjections) |
| Loads a SfM reconstruction from a file or files. This function loads a SfM reconstruction from three different file formats. The function detects the correct file format automatically, depending on the type (directory or file), and the headers of the files.
|
bool | readReconstruction_NVM (const QString fileName, QList< QString > &imageFiles, QList< QVMatrix > &cameraCalibrationMatrices, QList< QVCameraPose > &cameraPoses, QList< QV3DPointF > &points3D, QList< QColor > &rgbColors, QList< QHash< int, QPointF > > &pointTrackings) |
| Loads a SfM reconstruction from a NVM file.
|
Detailed Description
Several classes and functions related to structure from motion.
Function Documentation
QList<QVCameraPose> globalEpipolarAdjustment |
( |
const int |
numIterations, |
|
|
const QList< QVCameraPose > & |
initialCameraPoses, |
|
|
const QVDirectedGraph< QVMatrix > & |
reducedMatricesGraph, |
|
|
const QVector< bool > & |
freeCameras, |
|
|
const double |
lambda = 1e-3 , |
|
|
const bool |
adaptativeLambda = true , |
|
|
const TQVSparseSolve_Method |
solveMethod = DEFAULT_TQVSPARSESOLVE_METHOD , |
|
|
const int |
secondLevelIterations = 10 | |
|
) |
| | |
Refine the camera poses using epipolar geometry constraints.
This is the main function for GEA. Refines the set of camera poses, provided a directed graph containing the reduced M matrices representing the epipolar relationship between each pair of views in the reconstruction.
- Parameters:
-
| numIterations | Number of iterations to optimize the camera poses. |
| initialCameraPoses | Initial camera poses. One for each view. |
| reducedMatricesGraph | Directed graph containing a reduced matrix for each pair of views. |
| freeCameras | Vector containing a boolean for each camera, indicating wether this camera is fixed, or not in the optimization. Useful for incremental optimization. |
| lambda | Lambda parameter to increase the diagonal of the Hessian matrix. |
| adaptativeLambda | If true, the lambda value to increment the diagonal of the second level system is scaled with the mean value of the trace. Useful with reconstructions containing large number of views. |
| solveMethod | Method to solve the second level system. You need to configure QVision to use MKL or CHOLMOD (see file 'config.pri') in order to use MKL and CHOLMOD versions of the sparse solver. |
| secondLevelIterations | Number of iterations in the second level resolution of the linear system. Applied only when the param solveMethod is QVMKL_ISS or QVSCG. |
- Returns:
- list of optimized camera poses.
Definition at line 792 of file geaoptimization.cpp.
QList<QVCameraPose> globalEpipolarAdjustment |
( |
const int |
numIterations, |
|
|
const QList< QVCameraPose > & |
initialCameraPoses, |
|
|
const QVDirectedGraph< QVMatrix > & |
reducedMatricesGraph, |
|
|
const double |
lambda = 1e-3 , |
|
|
const bool |
adaptativeLambda = true , |
|
|
const TQVSparseSolve_Method |
solveMethod = DEFAULT_TQVSPARSESOLVE_METHOD , |
|
|
const int |
secondLevelIterations = 10 | |
|
) |
| | |
Refine the camera poses using epipolar geometry constraints.
This is an overloaded function provided by convenience. Every camera is included in the optimization, so no camera is fixed.
- See also:
- globalEpipolarAdjustment
- Parameters:
-
| numIterations | Number of iterations to optimize the camera poses. |
| initialCameraPoses | Initial camera poses. One for each view. |
| reducedMatricesGraph | Directed graph containing a reduced matrix for each pair of views. |
| lambda | Lambda parameter to increase the diagonal of the Hessian matrix. |
| adaptativeLambda | If true, the lambda value to increment the diagonal of the second level system is scaled with the mean value of the trace. Useful with reconstructions containing large number of views. |
| solveMethod | Method to solve the second level system. You need to configure QVision to use MKL or CHOLMOD (see file 'config.pri') in order to use MKL and CHOLMOD versions of the sparse solver. |
| secondLevelIterations | Number of iterations in the second level resolution of the linear system. Applied only when the param solveMethod is QVMKL_ISS or QVSCG. |
- Returns:
- list of optimized camera poses.
Definition at line 775 of file geaoptimization.cpp.
Referenced by globalEpipolarAdjustment().
QList<QVCameraPose> incrementalGEA |
( |
const int |
numIterations, |
|
|
const QList< QVCameraPose > & |
initialCameraPoses, |
|
|
const QVDirectedGraph< QVMatrix > & |
reducedMatricesGraph, |
|
|
const int |
numFreeCameras = 1 , |
|
|
const double |
lambda = 1e-3 , |
|
|
const bool |
adaptativeLambda = true , |
|
|
const TQVSparseSolve_Method |
solveMethod = DEFAULT_TQVSPARSESOLVE_METHOD , |
|
|
const int |
secondLevelIterations = 10 | |
|
) |
| | |
Incremental GEA refinement.
This function applies the GEA refinement on the view poses of a reconstruction. Unlike
- See also:
- globalEpipolarAdjustment this function optimizes the pose of a reduced set of the views in the reconstruction, leaving the rest of the poses unchanged. It can be used to perform real-time camera tracking. Optimizing the last views in the reconstruction (for example, the last 10 views added to the map) can be performed in real time, and prevents tracing failure significantly.
- Parameters:
-
| numIterations | Number of iterations to optimize the camera poses. |
| initialCameraPoses | Initial camera poses. One for each view. |
| reducedMatricesGraph | Directed graph containing a reduced matrix for each pair of views. |
| numFreeCameras | Number of views to optimize. The optimized views are the last ones inserted in the reconstruction (tail of initialCameraPoses list). |
| lambda | Lambda parameter to increase the diagonal of the Hessian matrix. |
| adaptativeLambda | If true, the lambda value added to the diagonal of the Hessian at the second level system is scaled with the mean value of the trace. Useful with reconstructions containing large number of views. |
| solveMethod | Method to solve the second level system. You need to configure QVision to use MKL or CHOLMOD (see file 'config.pri') in order to use MKL and CHOLMOD versions of the sparse solver. |
| secondLevelIterations | Number of iterations in the second level resolution of the linear system. Applied only when the param solveMethod is QVMKL_ISS or QVSCG. |
- Returns:
- list of optimized camera poses.
Definition at line 924 of file geaoptimization.cpp.
QVDirectedGraph<QVMatrix> getReducedMatrices |
( |
const QVDirectedGraph< QList< QPointFMatching > > & |
pointLists, |
|
|
const bool |
normalize = true , |
|
|
const TGEA_decomposition_method |
decomposition_method = GEA_CHOLESKY_DECOMPOSITION , |
|
|
const bool |
gsl = true , |
|
|
const double |
choleskyLambda = 0.0 , |
|
|
const int |
minPointCorrespondences = 0 | |
|
) |
| | |
Gets the reduced matrices for a reconstruction.
This function obtains the reduced matrices corresponding to each view pair in a reconstruction, provided the set of point correspondences between those view pairs.
- Parameters:
-
| pointLists | Contains the lists of point correspondences. |
| normalize | Perform pre-normalization of the point matchings. |
| decomposition_method | Select which decomposition of the reduced matrices is performed. |
| gsl | Select GSL to perform the decomposition. If false, LAPACK is used where available, which is a slower option for the size of the matrices to decompose (). |
| choleskyLambda | Adds this value to the diagonal elements of the reduced matrix before decomposing. Avoid decomposing singular matrices using cholesky. |
| minPointCorrespondences | Only reduced measurement matrices estimated from a number of point correspondences equal or larger to this value are included in the resulting graph. |
- Returns:
- A directed graph containing the reduced matrices.
Definition at line 142 of file geaoptimization.cpp.
QVDirectedGraph<QVMatrix> getReducedMatrices |
( |
const QVDirectedGraph< QVector< QPointFMatching > > & |
pointLists, |
|
|
const bool |
normalize = true , |
|
|
const TGEA_decomposition_method |
decomposition_method = GEA_CHOLESKY_DECOMPOSITION , |
|
|
const bool |
gsl = true , |
|
|
const double |
choleskyLambda = 0.0 , |
|
|
const int |
minPointCorrespondences = 0 | |
|
) |
| | |
Gets the reduced matrices for a reconstruction from the list of point correspondences detected between each view-pair in a reconstruction.
This function obtains the reduced matrices corresponding to each view pair in a reconstruction, provided the set of point correspondences between those view pairs.
- Parameters:
-
| pointLists | Contains the lists of point correspondences. |
| normalize | Perform pre-normalization of the point matchings. |
| decomposition_method | Select which decomposition of the reduced matrices is performed. |
| gsl | Select GSL to perform the decomposition. If false, LAPACK is used where available, which is a slower option for the size of the matrices to decompose (). |
| choleskyLambda | Adds this value to the diagonal elements of the reduced matrix before decomposing. Avoid decomposing singular matrices using Cholesky decomposition. |
| minPointCorrespondences | Only reduced measurement matrices estimated from a number of point correspondences equal or larger to this value are included in the resulting graph. |
- Returns:
- A directed graph containing the reduced matrices.
Definition at line 166 of file geaoptimization.cpp.
QVDirectedGraph< QList<QPointFMatching> > getPointMatchingsLists |
( |
const QList< QHash< int, QPointF > > |
pointProjections, |
|
|
const int |
numCams, |
|
|
const int |
minPointCorrespondences = 0 | |
|
) |
| | |
Obtains the list of point correspondences detected between each view-pair in a reconstruction.
This function obtains the reduced matrices corresponding to each view pair in a reconstruction, provided the set of point correspondences between those view pairs.
- Parameters:
-
| pointProjections | Data structure containing the point projections for each 3D point and view where it is visible. |
| numCams | Number of total views in the reconstruction. |
| munPointCorrespondences | Do not return point correspondence lists containing less than this quantity of point matchings. |
- Returns:
- A directed graph containing the lists of point correspondences.
Definition at line 49 of file geaoptimization.cpp.
QVDirectedGraph< QVector<QPointFMatching> > getPointMatchingsListsVec |
( |
const QList< QHash< int, QPointF > > |
pointProjections, |
|
|
const int |
numCams, |
|
|
const int |
minPointCorrespondences = 0 | |
|
) |
| | |
Obtains the list of point correspondences detected between each view-pair in a reconstruction.
This function obtains the reduced matrices corresponding to each view pair in a reconstruction, provided the set of point correspondences between those view pairs.
- Parameters:
-
| pointProjections | Data structure containing the point projections for each 3D point and view where it is visible. |
| numCams | Number of total views in the reconstruction. |
| munPointCorrespondences | Do not return point correspondence lists containing less than this quantity of point matchings. |
- Returns:
- A directed graph containing the lists of point correspondences.
Definition at line 330 of file geaoptimization.cpp.
QList< QHash< int, QPointF> > correctIntrinsics |
( |
const QList< QVMatrix > & |
Ks, |
|
|
const QList< QHash< int, QPointF > > & |
pointsProjections | |
|
) |
| | |
Corrects linear intrinsic calibration from a set of point projections.
- Todo:
- Document this.
Definition at line 143 of file qvsfm.cpp.
bool testCheirality |
( |
const QList< QVCameraPose > |
cameraPoses, |
|
|
const QList< QHash< int, QPointF > > |
calibratedPointsProjections | |
|
) |
| | |
Swaps the cheirality of the camera poses and 3D points contained in a SfM reconstruction.
- Todo:
- Document this.
Definition at line 178 of file qvsfm.cpp.
double reconstructionError |
( |
const QList< QVCameraPose > & |
cameraPoses, |
|
|
const QList< QV3DPointF > & |
points3D, |
|
|
const QList< QHash< int, QPointF > > & |
pointProjections | |
|
) |
| | |
Evaluate the mean reprojection error of a reconstruction.
- Todo:
- Document this.
Definition at line 266 of file qvsfm.cpp.
double reconstructionError |
( |
const QList< QVCameraPose > & |
cameraPoses, |
|
|
const QList< QHash< int, QPointF > > & |
pointProjections | |
|
) |
| | |
Evaluate the mean reprojection error of a reconstruction.
This is an overloaded version of the function reconstructionError which evaluates the reprojection error of a list of camera poses and a set of point trackings, estimating the point locations with a linear initialization.
- Todo:
- Document this.
Definition at line 192 of file qvsfm.cpp.
double reconstructionError |
( |
const QList< QVCameraPose > & |
cameraPoses, |
|
|
const QList< QV3DPointF > & |
points3D, |
|
|
const QList< QHash< int, QPointF > > & |
pointProjections, |
|
|
const QVector< bool > & |
evaluateTracking | |
|
) |
| | |
Evaluate the mean reprojection error of a pair-wise reconstruction.
- Todo:
- Document this.
Definition at line 288 of file qvsfm.cpp.
Evaluate the mean reprojection error of a pair-wise reconstruction.
- Todo:
- Document this.
Definition at line 309 of file qvsfm.cpp.
QVVector reconstructionErrorResiduals |
( |
const QList< QVCameraPose > & |
cameraPoses, |
|
|
const QList< QV3DPointF > & |
points3D, |
|
|
const QList< QHash< int, QPointF > > & |
pointTrackings | |
|
) |
| | |
Evaluate the residuals of a reconstruction.
- Todo:
- Document this.
Definition at line 327 of file qvsfm.cpp.
bool checkForNaNValues |
( |
const QList< QVCameraPose > & |
cameraPoses |
) |
|
Check for NaN values in a list of camera poses.
- Returns:
- true if any of the parameters of one or more of the camera poses contains a NaN value, false otherwise.
- Todo:
- Document this.
Definition at line 345 of file qvsfm.cpp.
bool checkForNaNValues |
( |
const QList< QV3DPointF > & |
points3D |
) |
|
Check for NaN values in a list of 3D points.
- Returns:
- true if any of the parameters of one or more of the points contains a NaN value, false otherwise.
- Todo:
- Document this.
Definition at line 360 of file qvsfm.cpp.
bool checkForNaNValues |
( |
const QList< QHash< int, QPointF > > & |
pointTrackings |
) |
|
Check for NaN values in a list of point trackings.
- Returns:
- true if any of the projections in the tracks contains a NaN value, false otherwise.
- Todo:
- Document this.
Definition at line 375 of file qvsfm.cpp.
Initialize the projection matrices of two views in a reconstruction, provided a list of point matchings.
- Parameters:
-
| matchings | List of point matchings detected between the two views. |
| Rt1 | Estimated projection matrix for first image. |
| Rt2 | Estimated projection matrix for second image. |
- Returns:
- true if the estimation was successful, false otherwise.
- Todo:
- Document this.
Definition at line 39 of file qvsfm.cpp.
bool readSfMReconstruction |
( |
const QString & |
path, |
|
|
QList< QVMatrix > & |
cameraCalibrations, |
|
|
QList< QVCameraPose > & |
cameraPoses, |
|
|
QList< QV3DPointF > & |
points3D, |
|
|
QList< QHash< int, QPointF > > & |
pointsProjections | |
|
) |
| | |
Loads a SfM reconstruction from a file or files. This function loads a SfM reconstruction from three different file formats. The function detects the correct file format automatically, depending on the type (directory or file), and the headers of the files.
The readable file formats are:
-
laSBA demo file format: the parameter path contains the path to a directory containing the following files:
- pts.txt (containing the points).
- cams.txt (containing the camera poses).
- calib.txt (containing the intrinsic calibration matrices for each camera).
The format of these files is the same used by the example applications included in the laSBA package. This is an extract from the file 'README.txt' describing these formats:
eucsbademo accepts 3 file names as arguments:
They are the initial estimates for the camera motion (i.e. pose) parameters, the initial
estimates for the 3D point parameters along with the 3D points image projections and the
camera intrinsic calibration parameters. The file for the camera motion parameters has a
separate line for every camera (i.e. frame), each line containing 7 parameters (a 4
element quaternion for rotation and a 3 element vector for translation). Rotation
quaternions have the scalar part as their first element, i.e. a rotation by angle TH
around the unit vector U=(Ux, Uy, Uz) should be specified as
cos(TH/2) Ux*sin(TH/2) Uy*sin(TH/2) Uz*sin(TH/2).
The file for 3D points and image projections is made up of lines of the form
X Y Z NFRAMES FRAME0 x0 y0 FRAME1 x1 y1 ...
each corresponding to a single 3D point. X Y Z are the points' Euclidean 3D coordinates,
NFRAMES the total number of images in which the points' projections are available and each
of the NFRAMES subsequent triplets FRAME x y specifies that the 3D point in question projects
to pixel x y in image FRAME. For example, the line
100.0 200.0 300.0 3 2 270.0 114.1 4 234.2 321.7 5 173.6 425.8
specifies the 3D point (100.0, 200.0, 300.0) projecting to the 3 points (270.0, 114.1),
(234.2, 321.7) and (173.6, 425.8) in images 2, 4 and 5 respectively. Pixel coordinates
are measured using the common convention, i.e. from the top left corner of images with
the positive x axis running from left to right and y from top to bottom. Camera and 3D
point indices count from 0.
-
BAITL data-set file format: The file specified in the path parameter must follow the format of the data-sets referenced by the paper Bundle Adjustment in the Large
These data-sets were obtained with the Bundler SfM system. You can find a description for this file format here.
-
Bundler output format: this is the standard file format for the output of the Bundler SfM system. A description of the format follows:
Bundler produces files typically called 'bundle_*.out' (we'll call
these "bundle files"). With the default commands, Bundler outputs a
bundle file called 'bundle_<n>.out' containing the current state of
the scene after each set of images has been registered (n = the number
of currently registered cameras). After all possible images have been
registered, Bundler outputs a final file named 'bundle.out'. In
addition, a "ply" file containing the reconstructed cameras and points
is written after each round. These ply files can be viewed with the
"scanalyze" mesh viewer, available at
http://graphics.stanford.edu/software/scanalyze/.
The bundle files contain the estimated scene and camera geometry have
the following format:
# Bundle file v0.3
<num_cameras> <num_points> [two integers]
<camera1>
<camera2>
...
<cameraN>
<point1>
<point2>
...
<pointM>
Each camera entry <cameraI> contains the estimated camera intrinsics
and extrinsics, and has the form:
<f> <k1> <k2> [the focal length, followed by two radial distortion coeffs]
<R> [a 3x3 matrix representing the camera rotation]
<t> [a 3-vector describing the camera translation]
The cameras are specified in the order they appear in the list of
images.
Each point entry <pointI> has the form:
<position> [a 3-vector describing the 3D position of the point]
<color> [a 3-vector describing the RGB color of the point]
<view list> [a list of views the point is visible in]
The view list begins with the length of the list (i.e., the number of
cameras the point is visible in). The list is then given as a list of
quadruplets <camera> <key> <x> <y>, where <camera> is a camera index,
<key> the index of the SIFT keypoint where the point was detected in
that camera, and <x> and <y> are the detected positions of that
keypoint. Both indices are 0-based (e.g., if camera 0 appears in the
list, this corresponds to the first camera in the scene file and the
first image in "list.txt").
We use a pinhole camera model; the parameters we estimate for each
camera are a focal length (f), two radial distortion parameters (k1
and k2), a rotation (R), and translation (t), as described in the file
specification above. The formula for projecting a 3D point X into a
camera (R, t, f) is:
P = R * X + t (conversion from world to camera coordinates)
p = -P / P.z (perspective division)
p' = f * r(p) * p (conversion to pixel coordinates)
where P.z is the third coordinate of P. In the last equation, r(p) is
a function that computes a scaling factor to undo the radial
distortion:
r(p) = 1.0 + k1 * ||p||^2 + k2 * ||p||^4.
This gives a projection in pixels, where the origin of the image is
the center of the image, the positive x-axis points right, and the
positive y-axis points up (in addition, in the camera coordinate
system, the positive z-axis points backwards, so the camera is looking
down the negative z-axis, as in OpenGL).
Finally, the equations above imply that the camera viewing direction
is:
R' * [0 0 -1]' (i.e., the third row of R or third column of R')
(where ' indicates the transpose of a matrix or vector).
and the 3D position of a camera is
-R' * t .
- Parameters:
-
| path | Path to the file (formats Bundler or BAITL), or directory (format laSBA) containing the files for the reconstruction. |
| cameraCalibrations | Output parameter containing the intrinsic calibration matrices for the cameras in the reconstruction. The list can contain either one matrix for each camera, or a single common calibration matrix for every view in the reconstruction if their calibration is the same. |
| cameraPoses | On output, contains the camera poses for the views in the reconstruction. |
| points3D | On output contains the 3D points. |
| pointsProjection | Output list. Each element contains the image projections of one of the 3D points, on each view it is visible. The projection of the i-th 3D point, on the j-th view can be accessed with the expression 'pointTrackings[i][j]'. |
Definition at line 816 of file readSfMReconstruction.cpp.
bool readReconstruction_NVM |
( |
const QString |
fileName, |
|
|
QList< QString > & |
imageFiles, |
|
|
QList< QVMatrix > & |
cameraCalibrationMatrices, |
|
|
QList< QVCameraPose > & |
cameraPoses, |
|
|
QList< QV3DPointF > & |
points3D, |
|
|
QList< QColor > & |
rgbColors, |
|
|
QList< QHash< int, QPointF > > & |
pointTrackings | |
|
) |
| | |
Loads a SfM reconstruction from a NVM file.
This function loads a SfM reconstruction from the reconstruction files provided by the Visual SfM application. The function detects the correct file format automatically, depending on the type (directory or file), and the headers of the files.
- Parameters:
-
| fileName | Path to the .NVM file containing the reconstruction. |
| imageFiles | List of paths to the input image files. |
| cameraCalibrations | Output parameter containing the intrinsic calibration matrices for the cameras in the reconstruction. The list can contain either one matrix for each camera, or a single common calibration matrix for every view in the reconstruction if their calibration is the same. |
| cameraPoses | On output, contains the camera poses for the views in the reconstruction. |
| points3D | On output contains the 3D points. |
| pointTrackings | Projection trackings for the 3D points. Each element in this list contains the image projections of one of the 3D points, on each view it is visible. The projection of the i-th 3D point, on the j-th view can be accessed with the expression 'pointTrackings[i][j]'. |
Definition at line 222 of file readSfMReconstruction.cpp.
|