Skip to content

Commit

Permalink
AR Demo
Browse files Browse the repository at this point in the history
  • Loading branch information
raulmur committed Dec 22, 2016
1 parent 689230f commit 80de336
Show file tree
Hide file tree
Showing 9 changed files with 147 additions and 18 deletions.
26 changes: 26 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,26 @@
CMakeLists.txt.user
Examples/Monocular/mono_euroc
Examples/Monocular/mono_kitti
Examples/Monocular/mono_tum
Examples/RGB-D/rgbd_tum
Examples/ROS/ORB_SLAM2/CMakeLists.txt.user
Examples/ROS/ORB_SLAM2/Mono
Examples/ROS/ORB_SLAM2/MonoAR
Examples/ROS/ORB_SLAM2/RGBD
Examples/ROS/ORB_SLAM2/Stereo
Examples/ROS/ORB_SLAM2/build/
Examples/ROS/ORB_SLAM2/src/AR/
Examples/Stereo/stereo_euroc
Examples/Stereo/stereo_kitti
KeyFrameTrajectory.txt
Thirdparty/DBoW2/build/
Thirdparty/DBoW2/lib/
Thirdparty/g2o/build/
Thirdparty/g2o/config.h
Thirdparty/g2o/lib/
Vocabulary/ORBvoc.txt
build/
build_ros.sh
*~
lib/

11 changes: 11 additions & 0 deletions Examples/ROS/ORB_SLAM2/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -59,6 +59,17 @@ target_link_libraries(Mono
${LIBS}
)

# Node for monocular camera (Augmented Reality Demo)
rosbuild_add_executable(MonoAR
src/AR/ros_mono_ar.cc
src/AR/ViewerAR.h
src/AR/ViewerAR.cc
)

target_link_libraries(MonoAR
${LIBS}
)

# Node for stereo camera
rosbuild_add_executable(Stereo
src/ros_stereo.cc
Expand Down
5 changes: 5 additions & 0 deletions include/Map.h
Original file line number Diff line number Diff line change
Expand Up @@ -45,6 +45,8 @@ class Map
void EraseMapPoint(MapPoint* pMP);
void EraseKeyFrame(KeyFrame* pKF);
void SetReferenceMapPoints(const std::vector<MapPoint*> &vpMPs);
void InformNewBigChange();
int GetLastBigChangeIdx();

std::vector<KeyFrame*> GetAllKeyFrames();
std::vector<MapPoint*> GetAllMapPoints();
Expand Down Expand Up @@ -72,6 +74,9 @@ class Map

long unsigned int mnMaxKFid;

// Index related to a big change in the map (loop closure, global BA)
int mnBigChangeIdx;

std::mutex mMutexMap;
};

Expand Down
16 changes: 16 additions & 0 deletions include/System.h
Original file line number Diff line number Diff line change
Expand Up @@ -82,6 +82,10 @@ class System
// This resumes local mapping thread and performs SLAM again.
void DeactivateLocalizationMode();

// Returns true if there have been a big map change (loop closure, global BA)
// since last call to this function
bool MapChanged();

// Reset the system (clear map)
void Reset();

Expand Down Expand Up @@ -112,6 +116,12 @@ class System
// SaveMap(const string &filename);
// LoadMap(const string &filename);

// Information from most recent processed frame
// You can call this right after TrackMonocular (or stereo or RGBD)
int GetTrackingState();
std::vector<MapPoint*> GetTrackedMapPoints();
std::vector<cv::KeyPoint> GetTrackedKeyPointsUn();

private:

// Input sensor
Expand Down Expand Up @@ -158,6 +168,12 @@ class System
std::mutex mMutexMode;
bool mbActivateLocalizationMode;
bool mbDeactivateLocalizationMode;

// Tracking state
int mTrackingState;
std::vector<MapPoint*> mTrackedMapPoints;
std::vector<cv::KeyPoint> mTrackedKeyPointsUn;
std::mutex mMutexState;
};

}// namespace ORB_SLAM
Expand Down
8 changes: 5 additions & 3 deletions src/LoopClosing.cc
Original file line number Diff line number Diff line change
Expand Up @@ -566,6 +566,8 @@ void LoopClosing::CorrectLoop()
// Optimize graph
Optimizer::OptimizeEssentialGraph(mpMap, mpMatchedKF, mpCurrentKF, NonCorrectedSim3, CorrectedSim3, LoopConnections, mbFixScale);

mpMap->InformNewBigChange();

// Add loop edge
mpMatchedKF->AddLoopEdge(mpCurrentKF);
mpCurrentKF->AddLoopEdge(mpMatchedKF);
Expand All @@ -579,8 +581,6 @@ void LoopClosing::CorrectLoop()
// Loop closed. Release Local Mapping.
mpLocalMapper->Release();

cout << "Loop Closed!" << endl;

mLastLoopKFid = mpCurrentKF->mnId;
}

Expand Down Expand Up @@ -734,7 +734,9 @@ void LoopClosing::RunGlobalBundleAdjustment(unsigned long nLoopKF)

pMP->SetWorldPos(Rwc*Xc+twc);
}
}
}

mpMap->InformNewBigChange();

mpLocalMapper->Release();

Expand Down
14 changes: 13 additions & 1 deletion src/Map.cc
Original file line number Diff line number Diff line change
Expand Up @@ -25,7 +25,7 @@
namespace ORB_SLAM2
{

Map::Map():mnMaxKFid(0)
Map::Map():mnMaxKFid(0),mnBigChangeIdx(0)
{
}

Expand Down Expand Up @@ -67,6 +67,18 @@ void Map::SetReferenceMapPoints(const vector<MapPoint *> &vpMPs)
mvpReferenceMapPoints = vpMPs;
}

void Map::InformNewBigChange()
{
unique_lock<mutex> lock(mMutexMap);
mnBigChangeIdx++;
}

int Map::GetLastBigChangeIdx()
{
unique_lock<mutex> lock(mMutexMap);
return mnBigChangeIdx;
}

vector<KeyFrame*> Map::GetAllKeyFrames()
{
unique_lock<mutex> lock(mMutexMap);
Expand Down
68 changes: 60 additions & 8 deletions src/System.cc
Original file line number Diff line number Diff line change
Expand Up @@ -30,7 +30,7 @@ namespace ORB_SLAM2
{

System::System(const string &strVocFile, const string &strSettingsFile, const eSensor sensor,
const bool bUseViewer):mSensor(sensor),mbReset(false),mbActivateLocalizationMode(false),
const bool bUseViewer):mSensor(sensor), mpViewer(static_cast<Viewer*>(NULL)), mbReset(false),mbActivateLocalizationMode(false),
mbDeactivateLocalizationMode(false)
{
// Output welcome message
Expand Down Expand Up @@ -95,11 +95,12 @@ System::System(const string &strVocFile, const string &strSettingsFile, const eS
mptLoopClosing = new thread(&ORB_SLAM2::LoopClosing::Run, mpLoopCloser);

//Initialize the Viewer thread and launch
mpViewer = new Viewer(this, mpFrameDrawer,mpMapDrawer,mpTracker,strSettingsFile);
if(bUseViewer)
{
mpViewer = new Viewer(this, mpFrameDrawer,mpMapDrawer,mpTracker,strSettingsFile);
mptViewer = new thread(&Viewer::Run, mpViewer);

mpTracker->SetViewer(mpViewer);
mpTracker->SetViewer(mpViewer);
}

//Set pointers between threads
mpTracker->SetLocalMapper(mpLocalMapper);
Expand Down Expand Up @@ -154,7 +155,13 @@ cv::Mat System::TrackStereo(const cv::Mat &imLeft, const cv::Mat &imRight, const
}
}

return mpTracker->GrabImageStereo(imLeft,imRight,timestamp);
cv::Mat Tcw = mpTracker->GrabImageStereo(imLeft,imRight,timestamp);

unique_lock<mutex> lock2(mMutexState);
mTrackingState = mpTracker->mState;
mTrackedMapPoints = mpTracker->mCurrentFrame.mvpMapPoints;
mTrackedKeyPointsUn = mpTracker->mCurrentFrame.mvKeysUn;
return Tcw;
}

cv::Mat System::TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const double &timestamp)
Expand Down Expand Up @@ -199,7 +206,13 @@ cv::Mat System::TrackRGBD(const cv::Mat &im, const cv::Mat &depthmap, const doub
}
}

return mpTracker->GrabImageRGBD(im,depthmap,timestamp);
cv::Mat Tcw = mpTracker->GrabImageRGBD(im,depthmap,timestamp);

unique_lock<mutex> lock2(mMutexState);
mTrackingState = mpTracker->mState;
mTrackedMapPoints = mpTracker->mCurrentFrame.mvpMapPoints;
mTrackedKeyPointsUn = mpTracker->mCurrentFrame.mvKeysUn;
return Tcw;
}

cv::Mat System::TrackMonocular(const cv::Mat &im, const double &timestamp)
Expand Down Expand Up @@ -244,7 +257,14 @@ cv::Mat System::TrackMonocular(const cv::Mat &im, const double &timestamp)
}
}

return mpTracker->GrabImageMonocular(im,timestamp);
cv::Mat Tcw = mpTracker->GrabImageMonocular(im,timestamp);

unique_lock<mutex> lock2(mMutexState);
mTrackingState = mpTracker->mState;
mTrackedMapPoints = mpTracker->mCurrentFrame.mvpMapPoints;
mTrackedKeyPointsUn = mpTracker->mCurrentFrame.mvKeysUn;

return Tcw;
}

void System::ActivateLocalizationMode()
Expand All @@ -259,6 +279,19 @@ void System::DeactivateLocalizationMode()
mbDeactivateLocalizationMode = true;
}

bool System::MapChanged()
{
static int n=0;
int curn = mpMap->GetLastBigChangeIdx();
if(n<curn)
{
n=curn;
return true;
}
else
return false;
}

void System::Reset()
{
unique_lock<mutex> lock(mMutexReset);
Expand All @@ -269,7 +302,8 @@ void System::Shutdown()
{
mpLocalMapper->RequestFinish();
mpLoopCloser->RequestFinish();
mpViewer->RequestFinish();
if(mpViewer)
mpViewer->RequestFinish();

// Wait until all thread have effectively stopped
while(!mpLocalMapper->isFinished() || !mpLoopCloser->isFinished() ||
Expand Down Expand Up @@ -433,4 +467,22 @@ void System::SaveTrajectoryKITTI(const string &filename)
cout << endl << "trajectory saved!" << endl;
}

int System::GetTrackingState()
{
unique_lock<mutex> lock(mMutexState);
return mTrackingState;
}

vector<MapPoint*> System::GetTrackedMapPoints()
{
unique_lock<mutex> lock(mMutexState);
return mTrackedMapPoints;
}

vector<cv::KeyPoint> System::GetTrackedKeyPointsUn()
{
unique_lock<mutex> lock(mMutexState);
return mTrackedKeyPointsUn;
}

} //namespace ORB_SLAM
14 changes: 9 additions & 5 deletions src/Tracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -45,7 +45,7 @@ namespace ORB_SLAM2

Tracking::Tracking(System *pSys, ORBVocabulary* pVoc, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Map *pMap, KeyFrameDatabase* pKFDB, const string &strSettingPath, const int sensor):
mState(NO_IMAGES_YET), mSensor(sensor), mbOnlyTracking(false), mbVO(false), mpORBVocabulary(pVoc),
mpKeyFrameDB(pKFDB), mpInitializer(static_cast<Initializer*>(NULL)), mpSystem(pSys),
mpKeyFrameDB(pKFDB), mpInitializer(static_cast<Initializer*>(NULL)), mpSystem(pSys), mpViewer(NULL),
mpFrameDrawer(pFrameDrawer), mpMapDrawer(pMapDrawer), mpMap(pMap), mnLastRelocFrameId(0)
{
// Load camera parameters from settings file
Expand Down Expand Up @@ -1503,11 +1503,14 @@ bool Tracking::Relocalization()

void Tracking::Reset()
{
mpViewer->RequestStop();

cout << "System Reseting" << endl;
while(!mpViewer->isStopped())
usleep(3000);
if(mpViewer)
{
mpViewer->RequestStop();
while(!mpViewer->isStopped())
usleep(3000);
}

// Reset Local Mapping
cout << "Reseting Local Mapper...";
Expand Down Expand Up @@ -1542,7 +1545,8 @@ void Tracking::Reset()
mlFrameTimes.clear();
mlbLost.clear();

mpViewer->Release();
if(mpViewer)
mpViewer->Release();
}

void Tracking::ChangeCalibration(const string &strSettingPath)
Expand Down
3 changes: 2 additions & 1 deletion src/Viewer.cc
Original file line number Diff line number Diff line change
Expand Up @@ -28,7 +28,7 @@ namespace ORB_SLAM2

Viewer::Viewer(System* pSystem, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer, Tracking *pTracking, const string &strSettingPath):
mpSystem(pSystem), mpFrameDrawer(pFrameDrawer),mpMapDrawer(pMapDrawer), mpTracker(pTracking),
mbFinishRequested(false), mbFinished(true), mbStopped(false), mbStopRequested(false)
mbFinishRequested(false), mbFinished(true), mbStopped(true), mbStopRequested(false)
{
cv::FileStorage fSettings(strSettingPath, cv::FileStorage::READ);

Expand All @@ -54,6 +54,7 @@ Viewer::Viewer(System* pSystem, FrameDrawer *pFrameDrawer, MapDrawer *pMapDrawer
void Viewer::Run()
{
mbFinished = false;
mbStopped = false;

pangolin::CreateWindowAndBind("ORB-SLAM2: Map Viewer",1024,768);

Expand Down

0 comments on commit 80de336

Please sign in to comment.