Jafar
|
Class IncrementalBundler, solves linearly the bundle adjustment problem only for the recovering 3D positions. More...
Class IncrementalBundler, solves linearly the bundle adjustment problem only for the recovering 3D positions.
For each view it requires
projection
matrix observed
pixel coordinatesData saving in this class is optional so be careful.
Definition at line 28 of file incrementalBundler.hpp.
#include <incrementalBundler.hpp>
Public Member Functions | |
IncrementalBundler () | |
default constructor | |
jblas::vec | solve () |
solves the system by means of LinearLeastSquares | |
jblas::vec3 | solution () |
double | reprojectionError () |
void | addEntry (const jblas::vec2 &pixel, const jblas::mat34 &projection) |
adds an entry to the system, no data is saved! | |
void | addEntry (int index, const jblas::vec2 &pixel, const jblas::mat34 &projection) |
adds an entry to the system and saves data with key index | |
void | addProjection (const jblas::mat34 &projection, const int &id) |
saves a projection matrix in IncrementalBundler indexed by id | |
void | addObservation (const jblas::vec2 &pixel, const int &view) |
saves a pixel observed in IncrementalBundler indexed by view | |
void | fill () |
fills system with saved pixels and projections | |
std::map< int, double > & | errors () |
bool | refine (const double &coef=1.5, size_t minentries=3) |
points that are coef times bigger than mean reprojection error are removed, system is reinitialized with remaining data. | |
double | tune (const double &wish=0.2, const double &coef=1.5, size_t minentries=3, int maxiter=10) |
automatically call refine() till | |
int | entries () const |
std::pair< jblas::mat34, jblas::vec2 > | data (int viewId) |
Private Attributes | |
std::map< int, jblas::mat34 > | m_projections |
map of the projections matrixes | |
std::map< int, jblas::vec2 > | m_pixels |
map of the observed pixels | |
std::map< int, double > | m_errors |
map of the projections errors | |
jblas::vec3 | m_solution |
computed center (solution of the system) | |
double | error |
mean reprojection error of the computed soltion | |
jmath::VariableSizeLinearLeastSquares2 | vlls |
variable size linear least squares solver |
std::map<int, double>& jafar::bundler::IncrementalBundler::errors | ( | ) | [inline] |
Definition at line 89 of file incrementalBundler.hpp.
References m_errors.
bool jafar::bundler::IncrementalBundler::refine | ( | const double & | coef = 1.5 , |
size_t | minentries = 3 |
||
) |
points that are coef times bigger than mean reprojection error are removed, system is reinitialized with remaining data.
This step could be iterated, externally, till satisfaction or no better result.
jblas::vec3 jafar::bundler::IncrementalBundler::solution | ( | ) | [inline] |
Definition at line 56 of file incrementalBundler.hpp.
References JFR_DEBUG, m_solution, and vlls.
jblas::vec jafar::bundler::IncrementalBundler::solve | ( | ) | [inline] |
solves the system by means of LinearLeastSquares
Definition at line 50 of file incrementalBundler.hpp.
double jafar::bundler::IncrementalBundler::tune | ( | const double & | wish = 0.2 , |
const double & | coef = 1.5 , |
||
size_t | minentries = 3 , |
||
int | maxiter = 10 |
||
) |
automatically call refine() till
desired
reprojection error wish is reached no
better result with the given coeffcient coef minimum
number of entries minentries is reached maximum
number of iterations maxiter is reached. Generated on Wed Oct 15 2014 00:37:32 for Jafar by doxygen 1.7.6.1 |