#include <MapMaker.h>
Classes | |
| struct | Command |
Public Member Functions | |
| void | AddKeyFrame (KeyFrame &k) |
| bool | InitFromStereo (KeyFrame &kFirst, KeyFrame &kSecond, std::vector< std::pair< CVD::ImageRef, CVD::ImageRef > > &vMatches, SE3<> &se3CameraPos, SE3<> KFZeroDesiredCamFromWorld, SE3<> KFOneDesiredCamFromWorld) |
| bool | InitFromStereo_OLD (KeyFrame &kFirst, KeyFrame &kSecond, std::vector< std::pair< CVD::ImageRef, CVD::ImageRef > > &vMatches, SE3<> &se3CameraPos) |
| bool | IsDistanceToNearestKeyFrameExcessive (KeyFrame &kCurrent) |
| MapMaker (Map &m, const ATANCamera &cam) | |
| bool | NeedNewKeyFrame (KeyFrame &kCurrent) |
| int | QueueSize () |
| void | RequestReset () |
| bool | ResetDone () |
| ~MapMaker () | |
Public Attributes | |
| double | currentScaleFactor |
| double | initialScaleFactor |
| double | lastMetricDist |
| double | lastWiggleDist |
| double | minKFDist |
| double | minKFWiggleDist |
Protected Member Functions | |
| void | AddKeyFrameFromTopOfQueue () |
| bool | AddPointEpipolar (KeyFrame &kSrc, KeyFrame &kTarget, int nLevel, int nCandidate) |
| void | AddSomeMapPoints (int nLevel) |
| void | ApplyGlobalScaleToMap (double dScale) |
| void | ApplyGlobalTransformationToMap (SE3<> se3NewFromOld) |
| void | BundleAdjust (std::set< KeyFrame * >, std::set< KeyFrame * >, std::set< MapPoint * >, bool) |
| void | BundleAdjustAll () |
| void | BundleAdjustRecent () |
| SE3 | CalcPlaneAligner () |
| KeyFrame * | ClosestKeyFrame (KeyFrame &k) |
| double | DistToNearestKeyFrame (KeyFrame &kCurrent) |
| void | GUICommandHandler (std::string sCommand, std::string sParams) |
| void | HandleBadPoints () |
| double | KeyFrameLinearDist (KeyFrame &k1, KeyFrame &k2) |
| std::vector< KeyFrame * > | NClosestKeyFrames (KeyFrame &k, unsigned int N) |
| bool | ReFind_Common (KeyFrame &k, MapPoint &p) |
| void | ReFindAll () |
| void | ReFindFromFailureQueue () |
| int | ReFindInSingleKeyFrame (KeyFrame &k) |
| void | ReFindNewlyMade () |
| void | RefreshSceneDepth (KeyFrame *pKF) |
| Vector< 3 > | ReprojectPoint (SE3<> se3AfromB, const Vector< 2 > &v2A, const Vector< 2 > &v2B) |
| void | Reset () |
| virtual void | run () |
| void | SubPixelRefineMatches (KeyFrame &k, int nLevel) |
| void | ThinCandidates (KeyFrame &k, int nLevel) |
Static Protected Member Functions | |
| static void | GUICommandCallBack (void *ptr, std::string sCommand, std::string sParams) |
Protected Attributes | |
| bool | mbBundleAbortRequested |
| bool | mbBundleConverged_Full |
| bool | mbBundleConverged_Recent |
| bool | mbBundleRunning |
| bool | mbBundleRunningIsRecent |
| bool | mbResetDone |
| bool | mbResetRequested |
| ATANCamera | mCamera |
| double | mdWiggleScale |
| double | mdWiggleScaleDepthNormalized |
| GVars3::gvar3< double > | mgvdWiggleScale |
| Map & | mMap |
| std::queue< MapPoint * > | mqNewQueue |
| std::vector< std::pair < KeyFrame *, MapPoint * > > | mvFailureQueue |
| std::vector< KeyFrame * > | mvpKeyFrameQueue |
| std::vector< Command > | mvQueuedCommands |
Definition at line 38 of file MapMaker.h.
| MapMaker::MapMaker | ( | Map & | m, |
| const ATANCamera & | cam | ||
| ) |
Definition at line 33 of file MapMaker.cc.
Definition at line 164 of file MapMaker.cc.
| void MapMaker::AddKeyFrame | ( | KeyFrame & | k | ) |
Definition at line 497 of file MapMaker.cc.
| void MapMaker::AddKeyFrameFromTopOfQueue | ( | ) | [protected] |
Definition at line 508 of file MapMaker.cc.
| bool MapMaker::AddPointEpipolar | ( | KeyFrame & | kSrc, |
| KeyFrame & | kTarget, | ||
| int | nLevel, | ||
| int | nCandidate | ||
| ) | [protected] |
Definition at line 541 of file MapMaker.cc.
| void MapMaker::AddSomeMapPoints | ( | int | nLevel | ) | [protected] |
Definition at line 444 of file MapMaker.cc.
| void MapMaker::ApplyGlobalScaleToMap | ( | double | dScale | ) | [protected] |
Definition at line 472 of file MapMaker.cc.
| void MapMaker::ApplyGlobalTransformationToMap | ( | SE3<> | se3NewFromOld | ) | [protected] |
Definition at line 457 of file MapMaker.cc.
| void MapMaker::BundleAdjust | ( | std::set< KeyFrame * > | , |
| std::set< KeyFrame * > | , | ||
| std::set< MapPoint * > | , | ||
| bool | |||
| ) | [protected] |
Definition at line 837 of file MapMaker.cc.
| void MapMaker::BundleAdjustAll | ( | ) | [protected] |
Definition at line 766 of file MapMaker.cc.
| void MapMaker::BundleAdjustRecent | ( | ) | [protected] |
Definition at line 787 of file MapMaker.cc.
| SE3 MapMaker::CalcPlaneAligner | ( | ) | [protected] |
Definition at line 1100 of file MapMaker.cc.
| KeyFrame * MapMaker::ClosestKeyFrame | ( | KeyFrame & | k | ) | [protected] |
Definition at line 724 of file MapMaker.cc.
| double MapMaker::DistToNearestKeyFrame | ( | KeyFrame & | kCurrent | ) | [protected] |
Definition at line 743 of file MapMaker.cc.
| void MapMaker::GUICommandCallBack | ( | void * | ptr, |
| std::string | sCommand, | ||
| std::string | sParams | ||
| ) | [static, protected] |
Definition at line 1226 of file MapMaker.cc.
| void MapMaker::GUICommandHandler | ( | std::string | sCommand, |
| std::string | sParams | ||
| ) | [protected] |
Definition at line 1234 of file MapMaker.cc.
| void MapMaker::HandleBadPoints | ( | ) | [protected] |
Definition at line 137 of file MapMaker.cc.
| bool MapMaker::InitFromStereo | ( | KeyFrame & | kFirst, |
| KeyFrame & | kSecond, | ||
| std::vector< std::pair< CVD::ImageRef, CVD::ImageRef > > & | vMatches, | ||
| SE3<> & | se3CameraPos, | ||
| SE3<> | KFZeroDesiredCamFromWorld, | ||
| SE3<> | KFOneDesiredCamFromWorld | ||
| ) |
Definition at line 198 of file MapMaker.cc.
| bool MapMaker::InitFromStereo_OLD | ( | KeyFrame & | kFirst, |
| KeyFrame & | kSecond, | ||
| std::vector< std::pair< CVD::ImageRef, CVD::ImageRef > > & | vMatches, | ||
| SE3<> & | se3CameraPos | ||
| ) |
| bool MapMaker::IsDistanceToNearestKeyFrameExcessive | ( | KeyFrame & | kCurrent | ) |
Definition at line 1094 of file MapMaker.cc.
| double MapMaker::KeyFrameLinearDist | ( | KeyFrame & | k1, |
| KeyFrame & | k2 | ||
| ) | [protected] |
Definition at line 695 of file MapMaker.cc.
| vector< KeyFrame * > MapMaker::NClosestKeyFrames | ( | KeyFrame & | k, |
| unsigned int | N | ||
| ) | [protected] |
Definition at line 704 of file MapMaker.cc.
| bool MapMaker::NeedNewKeyFrame | ( | KeyFrame & | kCurrent | ) |
Definition at line 750 of file MapMaker.cc.
| int MapMaker::QueueSize | ( | ) | [inline] |
Definition at line 59 of file MapMaker.h.
| bool MapMaker::ReFind_Common | ( | KeyFrame & | k, |
| MapPoint & | p | ||
| ) | [protected] |
Definition at line 959 of file MapMaker.cc.
| void MapMaker::ReFindAll | ( | ) | [protected] |
| void MapMaker::ReFindFromFailureQueue | ( | ) | [protected] |
Definition at line 1079 of file MapMaker.cc.
| int MapMaker::ReFindInSingleKeyFrame | ( | KeyFrame & | k | ) | [protected] |
Definition at line 1040 of file MapMaker.cc.
| void MapMaker::ReFindNewlyMade | ( | ) | [protected] |
Definition at line 1057 of file MapMaker.cc.
| void MapMaker::RefreshSceneDepth | ( | KeyFrame * | pKF | ) | [protected] |
Definition at line 1207 of file MapMaker.cc.
| Vector< 3 > MapMaker::ReprojectPoint | ( | SE3<> | se3AfromB, |
| const Vector< 2 > & | v2A, | ||
| const Vector< 2 > & | v2B | ||
| ) | [protected] |
Definition at line 175 of file MapMaker.cc.
| void MapMaker::RequestReset | ( | ) |
Definition at line 124 of file MapMaker.cc.
| void MapMaker::Reset | ( | ) | [protected] |
Definition at line 43 of file MapMaker.cc.
| bool MapMaker::ResetDone | ( | ) |
Definition at line 130 of file MapMaker.cc.
| void MapMaker::run | ( | ) | [protected, virtual] |
Definition at line 63 of file MapMaker.cc.
| void MapMaker::SubPixelRefineMatches | ( | KeyFrame & | k, |
| int | nLevel | ||
| ) | [protected] |
| void MapMaker::ThinCandidates | ( | KeyFrame & | k, |
| int | nLevel | ||
| ) | [protected] |
Definition at line 406 of file MapMaker.cc.
| double MapMaker::currentScaleFactor |
Definition at line 64 of file MapMaker.h.
| double MapMaker::initialScaleFactor |
Definition at line 63 of file MapMaker.h.
| double MapMaker::lastMetricDist |
Definition at line 67 of file MapMaker.h.
| double MapMaker::lastWiggleDist |
Definition at line 68 of file MapMaker.h.
bool MapMaker::mbBundleAbortRequested [protected] |
Definition at line 136 of file MapMaker.h.
bool MapMaker::mbBundleConverged_Full [protected] |
Definition at line 130 of file MapMaker.h.
bool MapMaker::mbBundleConverged_Recent [protected] |
Definition at line 131 of file MapMaker.h.
bool MapMaker::mbBundleRunning [protected] |
Definition at line 137 of file MapMaker.h.
bool MapMaker::mbBundleRunningIsRecent [protected] |
Definition at line 138 of file MapMaker.h.
bool MapMaker::mbResetDone [protected] |
Definition at line 135 of file MapMaker.h.
bool MapMaker::mbResetRequested [protected] |
Definition at line 134 of file MapMaker.h.
ATANCamera MapMaker::mCamera [protected] |
Definition at line 73 of file MapMaker.h.
double MapMaker::mdWiggleScale [protected] |
Definition at line 124 of file MapMaker.h.
double MapMaker::mdWiggleScaleDepthNormalized [protected] |
Definition at line 127 of file MapMaker.h.
GVars3::gvar3<double> MapMaker::mgvdWiggleScale [protected] |
Definition at line 126 of file MapMaker.h.
| double MapMaker::minKFDist |
Definition at line 66 of file MapMaker.h.
| double MapMaker::minKFWiggleDist |
Definition at line 65 of file MapMaker.h.
Map& MapMaker::mMap [protected] |
Definition at line 72 of file MapMaker.h.
std::queue<MapPoint*> MapMaker::mqNewQueue [protected] |
Definition at line 122 of file MapMaker.h.
std::vector<std::pair<KeyFrame*, MapPoint*> > MapMaker::mvFailureQueue [protected] |
Definition at line 121 of file MapMaker.h.
std::vector<KeyFrame*> MapMaker::mvpKeyFrameQueue [protected] |
Definition at line 120 of file MapMaker.h.
std::vector<Command> MapMaker::mvQueuedCommands [protected] |
Definition at line 116 of file MapMaker.h.