Skip to content

Commit

Permalink
Fix two segfaults; Save and load works now for large maps!
Browse files Browse the repository at this point in the history
  • Loading branch information
lennarthaller committed Jul 25, 2019
1 parent 8728603 commit d3c2d44
Show file tree
Hide file tree
Showing 3 changed files with 59 additions and 2 deletions.
5 changes: 5 additions & 0 deletions orb_slam2/include/System.h
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,7 @@
#include<thread>
#include <unistd.h>
#include<opencv2/core/core.hpp>
#include <sys/resource.h>

#include "Tracking.h"
#include "FrameDrawer.h"
Expand Down Expand Up @@ -129,6 +130,10 @@ class System
std::vector<MapPoint*> GetAllMapPoints();

private:
bool SetCallStackSize (const rlim_t kNewStackSize);

rlim_t GetCurrentCallStackSize ();

// This stops local mapping thread (map building) and performs only camera tracking.
void ActivateLocalizationMode();

Expand Down
55 changes: 53 additions & 2 deletions orb_slam2/src/System.cc
Original file line number Diff line number Diff line change
Expand Up @@ -497,6 +497,49 @@ std::vector<MapPoint*> System::GetAllMapPoints() {
return mpMap->GetAllMapPoints();
}


bool System::SetCallStackSize (const rlim_t kNewStackSize) {
struct rlimit rlimit;
int operation_result;

operation_result = getrlimit(RLIMIT_STACK, &rlimit);
if (operation_result != 0) {
std::cerr << "Error getting the call stack struct" << std::endl;
return false;
}

if (kNewStackSize > rlimit.rlim_max) {
std::cerr << "Requested call stack size too large" << std::endl;
return false;
}

if (rlimit.rlim_cur < kNewStackSize) {
rlimit.rlim_cur = kNewStackSize;
operation_result = setrlimit(RLIMIT_STACK, &rlimit);
if (operation_result != 0) {
std::cerr << "Setrlimit returned result: " << operation_result << std::endl;
return false;
}
return true;
}
return false;
}


rlim_t System::GetCurrentCallStackSize () {
struct rlimit rlimit;
int operation_result;

operation_result = getrlimit(RLIMIT_STACK, &rlimit);
if (operation_result != 0) {
std::cerr << "Error getting the call stack struct" << std::endl;
return 16 * 1024L * 1024L; //default
}

return rlimit.rlim_cur;
}


void System::ActivateLocalizationMode()
{
currently_localizing_only_ = true;
Expand Down Expand Up @@ -527,30 +570,38 @@ void System::EnableLocalizationOnly (bool localize_only) {

// map serialization addition
bool System::SaveMap(const string &filename) {

unique_lock<mutex>MapPointGlobal(MapPoint::mGlobalMutex);
std::ofstream out(filename, std::ios_base::binary);
if (!out) {
std::cerr << "cannot write to map file: " << map_file << std::endl;
return false;
}

const rlim_t kNewStackSize = 64L * 1024L * 1024L; // min stack size = 64 Mb
const rlim_t kDefaultCallStackSize = GetCurrentCallStackSize();
if (!SetCallStackSize(kNewStackSize)) {
std::cerr << "Error changing the call stack size; Aborting" << std::endl;
return false;
}

try {
std::cout << "saving map file: " << map_file << std::flush;
boost::archive::binary_oarchive oa(out, boost::archive::no_header);
oa << mpMap;
oa << mpKeyFrameDatabase;
std::cout << " ... done" << std::endl;
out.close();

} catch (const std::exception &e) {
std::cerr << e.what() << std::endl;
SetCallStackSize(kDefaultCallStackSize);
return false;
} catch (...) {
std::cerr << "Unknows exeption" << std::endl;
SetCallStackSize(kDefaultCallStackSize);
return false;
}

SetCallStackSize(kDefaultCallStackSize);
return true;
}

Expand Down
1 change: 1 addition & 0 deletions orb_slam2/src/Tracking.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1486,6 +1486,7 @@ bool Tracking::Relocalization()

if(!bMatch)
{
mCurrentFrame.mTcw = cv::Mat::zeros(0, 0, CV_32F); // this prevents a segfault later (https://github.com/raulmur/ORB_SLAM2/pull/381#issuecomment-337312336)
return false;
}
else
Expand Down

0 comments on commit d3c2d44

Please sign in to comment.