#include <MapMaker.h>
Classes | |
| struct | Command |
Public Member Functions | |
| void | AddKeyFrame (KeyFrame::Ptr k) |
| void | ApplyGlobalScaleToMap (double dScale) |
| void | ApplyGlobalTransformationToMap (SE3<> se3NewFromOld) |
| KeyFrame::Ptr | ClosestKeyFrame (KeyFrame::Ptr k) |
| std::string | getMessageForUser () |
| bool | InitFromStereo (KeyFrame::Ptr kFirst, KeyFrame::Ptr kSecond, std::vector< std::pair< CVD::ImageRef, CVD::ImageRef > > &vMatches, SE3<> &se3CameraPos) |
| bool | InitFromStereo_OLD (KeyFrame::Ptr kFirst, KeyFrame::Ptr kSecond, std::vector< std::pair< CVD::ImageRef, CVD::ImageRef > > &vMatches, SE3<> &se3CameraPos) |
| bool | IsDistanceToNearestKeyFrameExcessive (KeyFrame::Ptr kCurrent) |
| MapMaker (Map &m, const ATANCamera &cam, ros::NodeHandle &nh) | |
| std::vector< KeyFrame::Ptr > | NClosestKeyFrames (KeyFrame::Ptr k, unsigned int N) |
| bool | NeedNewKeyFrame (KeyFrame::Ptr kCurrent) |
| int | QueueSize () |
| void | RequestReset () |
| bool | ResetDone () |
| void | resetMessageForUser () |
| ~MapMaker () | |
Protected Member Functions | |
| void | AddKeyFrameFromTopOfQueue () |
| bool | AddPointEpipolar (KeyFrame::Ptr kSrc, KeyFrame::Ptr kTarget, int nLevel, int nCandidate) |
| bool | AddSomeMapPoints (int nLevel) |
| void | BundleAdjust (std::set< KeyFrame::Ptr >, std::set< KeyFrame::Ptr >, std::set< boost::shared_ptr< MapPoint > >, bool) |
| void | BundleAdjustAll () |
| void | BundleAdjustRecent () |
| SE3 | CalcPlaneAligner () |
| double | DistToNearestKeyFrame (KeyFrame::Ptr kCurrent) |
| void | GUICommandHandler (std::string sCommand, std::string sParams) |
| void | HandleBadPoints () |
| double | KeyFrameLinearDist (KeyFrame::Ptr k1, KeyFrame::Ptr k2) |
| bool | ReFind_Common (KeyFrame::Ptr k, boost::shared_ptr< MapPoint > p) |
| void | ReFindAll () |
| void | ReFindFromFailureQueue () |
| int | ReFindInSingleKeyFrame (KeyFrame::Ptr k) |
| void | ReFindNewlyMade () |
| bool | RefreshSceneDepth (KeyFrame::Ptr pKF) |
| Vector< 3 > | ReprojectPoint (SE3<> se3AfromB, const Vector< 2 > &v2A, const Vector< 2 > &v2B) |
| void | Reset () |
| virtual void | run () |
| void | SubPixelRefineMatches (KeyFrame::Ptr k, int nLevel) |
| void | ThinCandidates (KeyFrame::Ptr 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 |
| Map & | mMap |
| std::ostringstream | mMessageForUser |
| std::queue< boost::shared_ptr < MapPoint > > | mqNewQueue |
| std::vector< std::pair < KeyFrame::Ptr, boost::shared_ptr< MapPoint > > > | mvFailureQueue |
| std::vector< KeyFrame::Ptr > | mvpKeyFrameQueue |
| std::vector< Command > | mvQueuedCommands |
| OctoMapInterface | octomap_interface |
Definition at line 42 of file MapMaker.h.
| MapMaker::MapMaker | ( | Map & | m, |
| const ATANCamera & | cam, | ||
| ros::NodeHandle & | nh | ||
| ) |
Definition at line 39 of file MapMaker.cc.
Definition at line 208 of file MapMaker.cc.
| void MapMaker::AddKeyFrame | ( | KeyFrame::Ptr | k | ) |
Definition at line 586 of file MapMaker.cc.
| void MapMaker::AddKeyFrameFromTopOfQueue | ( | ) | [protected] |
Definition at line 595 of file MapMaker.cc.
| bool MapMaker::AddPointEpipolar | ( | KeyFrame::Ptr | kSrc, |
| KeyFrame::Ptr | kTarget, | ||
| int | nLevel, | ||
| int | nCandidate | ||
| ) | [protected] |
Definition at line 679 of file MapMaker.cc.
| bool MapMaker::AddSomeMapPoints | ( | int | nLevel | ) | [protected] |
Definition at line 537 of file MapMaker.cc.
| void MapMaker::ApplyGlobalScaleToMap | ( | double | dScale | ) |
Definition at line 568 of file MapMaker.cc.
| void MapMaker::ApplyGlobalTransformationToMap | ( | SE3<> | se3NewFromOld | ) |
Definition at line 553 of file MapMaker.cc.
| void MapMaker::BundleAdjust | ( | std::set< KeyFrame::Ptr > | , |
| std::set< KeyFrame::Ptr > | , | ||
| std::set< boost::shared_ptr< MapPoint > > | , | ||
| bool | |||
| ) | [protected] |
Definition at line 1030 of file MapMaker.cc.
| void MapMaker::BundleAdjustAll | ( | ) | [protected] |
Definition at line 949 of file MapMaker.cc.
| void MapMaker::BundleAdjustRecent | ( | ) | [protected] |
Definition at line 970 of file MapMaker.cc.
| SE3 MapMaker::CalcPlaneAligner | ( | ) | [protected] |
Definition at line 1323 of file MapMaker.cc.
Definition at line 880 of file MapMaker.cc.
| double MapMaker::DistToNearestKeyFrame | ( | KeyFrame::Ptr | kCurrent | ) | [protected] |
Definition at line 899 of file MapMaker.cc.
| std::string MapMaker::getMessageForUser | ( | ) | [inline] |
Definition at line 65 of file MapMaker.h.
| void MapMaker::GUICommandCallBack | ( | void * | ptr, |
| std::string | sCommand, | ||
| std::string | sParams | ||
| ) | [static, protected] |
Definition at line 1457 of file MapMaker.cc.
| void MapMaker::GUICommandHandler | ( | std::string | sCommand, |
| std::string | sParams | ||
| ) | [protected] |
Definition at line 1465 of file MapMaker.cc.
| void MapMaker::HandleBadPoints | ( | ) | [protected] |
Definition at line 154 of file MapMaker.cc.
| bool MapMaker::InitFromStereo | ( | KeyFrame::Ptr | kFirst, |
| KeyFrame::Ptr | kSecond, | ||
| std::vector< std::pair< CVD::ImageRef, CVD::ImageRef > > & | vMatches, | ||
| SE3<> & | se3CameraPos | ||
| ) |
Definition at line 242 of file MapMaker.cc.
| bool MapMaker::InitFromStereo_OLD | ( | KeyFrame::Ptr | kFirst, |
| KeyFrame::Ptr | kSecond, | ||
| std::vector< std::pair< CVD::ImageRef, CVD::ImageRef > > & | vMatches, | ||
| SE3<> & | se3CameraPos | ||
| ) |
| bool MapMaker::IsDistanceToNearestKeyFrameExcessive | ( | KeyFrame::Ptr | kCurrent | ) |
Definition at line 1317 of file MapMaker.cc.
| double MapMaker::KeyFrameLinearDist | ( | KeyFrame::Ptr | k1, |
| KeyFrame::Ptr | k2 | ||
| ) | [protected] |
Definition at line 851 of file MapMaker.cc.
| vector< KeyFrame::Ptr > MapMaker::NClosestKeyFrames | ( | KeyFrame::Ptr | k, |
| unsigned int | N | ||
| ) |
Definition at line 860 of file MapMaker.cc.
| bool MapMaker::NeedNewKeyFrame | ( | KeyFrame::Ptr | kCurrent | ) |
Definition at line 906 of file MapMaker.cc.
| int MapMaker::QueueSize | ( | ) | [inline] |
Definition at line 61 of file MapMaker.h.
| bool MapMaker::ReFind_Common | ( | KeyFrame::Ptr | k, |
| boost::shared_ptr< MapPoint > | p | ||
| ) | [protected] |
Definition at line 1175 of file MapMaker.cc.
| void MapMaker::ReFindAll | ( | ) | [protected] |
| void MapMaker::ReFindFromFailureQueue | ( | ) | [protected] |
Definition at line 1302 of file MapMaker.cc.
| int MapMaker::ReFindInSingleKeyFrame | ( | KeyFrame::Ptr | k | ) | [protected] |
Definition at line 1263 of file MapMaker.cc.
| void MapMaker::ReFindNewlyMade | ( | ) | [protected] |
Definition at line 1280 of file MapMaker.cc.
| bool MapMaker::RefreshSceneDepth | ( | KeyFrame::Ptr | pKF | ) | [protected] |
Definition at line 1434 of file MapMaker.cc.
| Vector< 3 > MapMaker::ReprojectPoint | ( | SE3<> | se3AfromB, |
| const Vector< 2 > & | v2A, | ||
| const Vector< 2 > & | v2B | ||
| ) | [protected] |
Definition at line 219 of file MapMaker.cc.
| void MapMaker::RequestReset | ( | ) |
Definition at line 141 of file MapMaker.cc.
| void MapMaker::Reset | ( | ) | [protected] |
Definition at line 50 of file MapMaker.cc.
| bool MapMaker::ResetDone | ( | ) |
Definition at line 147 of file MapMaker.cc.
| void MapMaker::resetMessageForUser | ( | ) | [inline] |
Definition at line 66 of file MapMaker.h.
| void MapMaker::run | ( | ) | [protected, virtual] |
Definition at line 70 of file MapMaker.cc.
| void MapMaker::SubPixelRefineMatches | ( | KeyFrame::Ptr | k, |
| int | nLevel | ||
| ) | [protected] |
| void MapMaker::ThinCandidates | ( | KeyFrame::Ptr | k, |
| int | nLevel | ||
| ) | [protected] |
Definition at line 499 of file MapMaker.cc.
bool MapMaker::mbBundleAbortRequested [protected] |
Definition at line 141 of file MapMaker.h.
bool MapMaker::mbBundleConverged_Full [protected] |
Definition at line 135 of file MapMaker.h.
bool MapMaker::mbBundleConverged_Recent [protected] |
Definition at line 136 of file MapMaker.h.
bool MapMaker::mbBundleRunning [protected] |
Definition at line 142 of file MapMaker.h.
bool MapMaker::mbBundleRunningIsRecent [protected] |
Definition at line 143 of file MapMaker.h.
bool MapMaker::mbResetDone [protected] |
Definition at line 140 of file MapMaker.h.
bool MapMaker::mbResetRequested [protected] |
Definition at line 139 of file MapMaker.h.
ATANCamera MapMaker::mCamera [protected] |
Definition at line 78 of file MapMaker.h.
double MapMaker::mdWiggleScale [protected] |
Definition at line 129 of file MapMaker.h.
double MapMaker::mdWiggleScaleDepthNormalized [protected] |
Definition at line 132 of file MapMaker.h.
Map& MapMaker::mMap [protected] |
Definition at line 77 of file MapMaker.h.
std::ostringstream MapMaker::mMessageForUser [protected] |
Definition at line 146 of file MapMaker.h.
std::queue<boost::shared_ptr<MapPoint> > MapMaker::mqNewQueue [protected] |
Definition at line 127 of file MapMaker.h.
std::vector<std::pair<KeyFrame::Ptr, boost::shared_ptr<MapPoint> > > MapMaker::mvFailureQueue [protected] |
Definition at line 126 of file MapMaker.h.
std::vector<KeyFrame::Ptr> MapMaker::mvpKeyFrameQueue [protected] |
Definition at line 125 of file MapMaker.h.
std::vector<Command> MapMaker::mvQueuedCommands [protected] |
Definition at line 121 of file MapMaker.h.
OctoMapInterface MapMaker::octomap_interface [protected] |
Definition at line 82 of file MapMaker.h.