#include <Bundle.h>
Public Member Functions | |
| int | AddCamera (SE3<> se3CamFromWorld, bool bFixed) |
| void | AddMeas (int nCam, int nPoint, Vector< 2 > v2Pos, double dSigmaSquared) |
| int | AddPoint (Vector< 3 > v3Pos) |
| Bundle (const ATANCamera &TCam) | |
| int | Compute (bool *pbAbortSignal) |
| bool | Converged () |
| SE3 | GetCamera (int n) |
| std::vector< std::pair< int, int > > | GetOutlierMeasurements () |
| std::set< int > | GetOutliers () |
| Vector< 3 > | GetPoint (int n) |
Protected Member Functions | |
| void | ClearAccumulators () |
| template<class MEstimator > | |
| bool | Do_LM_Step (bool *pbAbortSignal) |
| template<class MEstimator > | |
| double | FindNewError () |
| void | GenerateMeasLUTs () |
| void | GenerateOffDiagScripts () |
| void | ModifyLambda_BadStep () |
| void | ModifyLambda_GoodStep () |
| void | ProjectAndFindSquaredError (Meas &meas) |
Protected Attributes | |
| bool | mbConverged |
| bool | mbHitMaxIterations |
| ATANCamera | mCamera |
| double | mdLambda |
| double | mdLambdaFactor |
| double | mdSigmaSquared |
| GVars3::gvar3< double > | mgvdUpdateConvergenceLimit |
| GVars3::gvar3< int > | mgvnBundleCout |
| GVars3::gvar3< int > | mgvnMaxIterations |
| std::list< Meas > | mMeasList |
| int | mnAccepted |
| int | mnCamsToUpdate |
| int | mnCounter |
| int | mnStartRow |
| bool * | mpbAbortSignal |
| std::vector< Camera > | mvCameras |
| std::vector< std::vector< Meas * > > | mvMeasLUTs |
| std::vector< std::pair< int, int > > | mvOutlierMeasurementIdx |
| std::vector< Point > | mvPoints |
| Bundle::Bundle | ( | const ATANCamera & | TCam | ) |
| int Bundle::AddCamera | ( | SE3<> | se3CamFromWorld, |
| bool | bFixed | ||
| ) |
| void Bundle::AddMeas | ( | int | nCam, |
| int | nPoint, | ||
| Vector< 2 > | v2Pos, | ||
| double | dSigmaSquared | ||
| ) |
| int Bundle::AddPoint | ( | Vector< 3 > | v3Pos | ) |
| void Bundle::ClearAccumulators | ( | ) | [protected] |
| int Bundle::Compute | ( | bool * | pbAbortSignal | ) |
| bool Bundle::Converged | ( | ) | [inline] |
| bool Bundle::Do_LM_Step | ( | bool * | pbAbortSignal | ) | [protected] |
| double Bundle::FindNewError | ( | ) | [protected] |
| void Bundle::GenerateMeasLUTs | ( | ) | [protected] |
| void Bundle::GenerateOffDiagScripts | ( | ) | [protected] |
| SE3 Bundle::GetCamera | ( | int | n | ) |
| vector< pair< int, int > > Bundle::GetOutlierMeasurements | ( | ) |
| set< int > Bundle::GetOutliers | ( | ) |
| Vector< 3 > Bundle::GetPoint | ( | int | n | ) |
| void Bundle::ModifyLambda_BadStep | ( | ) | [protected] |
| void Bundle::ModifyLambda_GoodStep | ( | ) | [protected] |
| void Bundle::ProjectAndFindSquaredError | ( | Meas & | meas | ) | [inline, protected] |
bool Bundle::mbConverged [protected] |
bool Bundle::mbHitMaxIterations [protected] |
ATANCamera Bundle::mCamera [protected] |
double Bundle::mdLambda [protected] |
double Bundle::mdLambdaFactor [protected] |
double Bundle::mdSigmaSquared [protected] |
GVars3::gvar3<double> Bundle::mgvdUpdateConvergenceLimit [protected] |
GVars3::gvar3<int> Bundle::mgvnBundleCout [protected] |
GVars3::gvar3<int> Bundle::mgvnMaxIterations [protected] |
std::list<Meas> Bundle::mMeasList [protected] |
int Bundle::mnAccepted [protected] |
int Bundle::mnCamsToUpdate [protected] |
int Bundle::mnCounter [protected] |
int Bundle::mnStartRow [protected] |
bool* Bundle::mpbAbortSignal [protected] |
std::vector<Camera> Bundle::mvCameras [protected] |
std::vector<std::vector<Meas*> > Bundle::mvMeasLUTs [protected] |
std::vector<std::pair<int,int> > Bundle::mvOutlierMeasurementIdx [protected] |
std::vector<Point> Bundle::mvPoints [protected] |